-
Notifications
You must be signed in to change notification settings - Fork 12
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #60 from osrf/jessica/mwes
2023 minimum working example
- Loading branch information
Showing
14 changed files
with
263 additions
and
96 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,108 @@ | ||
import rclpy | ||
from rclpy.node import Node | ||
from ros_gz_interfaces.msg import ParamVec | ||
from std_msgs.msg import Float64 | ||
from rclpy.qos import QoSProfile, QoSDurabilityPolicy | ||
from geometry_msgs.msg import PoseStamped | ||
|
||
class GhostShip(Node): | ||
def __init__(self): | ||
print('Starting node...') | ||
super().__init__('ghost_ship') | ||
self.task_type = "" | ||
self.task_state = "" | ||
self.task_sub = self.create_subscription(ParamVec, '/vrx/task/info', | ||
self.taskCB, 10) | ||
|
||
pub_qos = QoSProfile(depth=1, | ||
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL) | ||
self.right_thrust_pub = self.create_publisher(Float64, | ||
'/wamv/thrusters/right/thrust', | ||
qos_profile=pub_qos) | ||
self.left_thrust_pub = self.create_publisher(Float64, | ||
'/wamv/thrusters/left/thrust', | ||
qos_profile=pub_qos) | ||
self.thrust_msg = Float64() | ||
self.thrust_msg.data = 30.0 | ||
self.loopCount = 0 | ||
|
||
self.landmark_pub = self.create_publisher(PoseStamped, | ||
'/vrx/perception/landmark', | ||
qos_profile=pub_qos) | ||
self.landmark_msg = PoseStamped() | ||
self.landmark_msg.header.stamp = self.get_clock().now().to_msg() | ||
self.landmark_msg.header.frame_id = 'mb_marker_buoy_red' | ||
self.landmark_msg.pose.position.x = -33.7227024 | ||
self.landmark_msg.pose.position.y = 150.67402097 | ||
self.landmark_msg.pose.position.z = 0.0 | ||
|
||
self.create_timer(0.5, self.sendCmds) | ||
|
||
def taskCB(self, msg): | ||
task_info = msg.params | ||
for p in task_info: | ||
if p.name == 'name': | ||
self.task_type = p.value .string_value | ||
if p.name == 'state': | ||
self.task_state = p.value.string_value | ||
|
||
def moveForward(self): | ||
self.right_thrust_pub.publish(self.thrust_msg) | ||
self.left_thrust_pub.publish(self.thrust_msg) | ||
self.loopCount += 1 | ||
|
||
def stop(self): | ||
self.thrust_msg.data = 0.0 | ||
self.right_thrust_pub.publish(self.thrust_msg) | ||
self.left_thrust_pub.publish(self.thrust_msg) | ||
|
||
def publishBuoyLoc(self): | ||
if self.loopCount > 10: | ||
self.landmark_pub.publish(self.landmark_msg) | ||
self.loopCount = 0 | ||
self.loopCount += 1 | ||
|
||
|
||
|
||
def sendCmds(self): | ||
if rclpy.ok(): | ||
match self.task_type: | ||
case "perception": | ||
if self.task_state == ("initial" or "ready"): | ||
print("Waiting for perception task to start...") | ||
elif self.task_state == "running": | ||
self.publishBuoyLoc() | ||
elif self.task_state == "finished": | ||
print("Task ended...") | ||
rclpy.shutdown() | ||
case "stationkeeping": | ||
if self.task_state == ("initial" or "ready"): | ||
print("Waiting for stationkeeping task to start...") | ||
elif self.task_state == "running": | ||
if self.loopCount < 10: | ||
self.moveForward() | ||
else: | ||
self.stop() | ||
elif self.task_state == "finished": | ||
print("Task ended...") | ||
rclpy.shutdown() | ||
case _: | ||
print(self.task_state) | ||
if self.task_state == ("initial" or "ready"): | ||
print("Waiting for default task to start...") | ||
elif self.task_state == "running": | ||
self.right_thrust_pub.publish(self.thrust_msg) | ||
self.left_thrust_pub.publish(self.thrust_msg) | ||
elif self.task_state == "finished": | ||
print("Task ended...") | ||
rclpy.shutdown() | ||
|
||
def main(args=None): | ||
rclpy.init(args=args) | ||
|
||
ghost_ship = GhostShip() | ||
rclpy.spin(ghost_ship) | ||
|
||
|
||
if __name__ == '__main__': | ||
main() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1 +1 @@ | ||
crvogt/vrx_2022_simple | ||
jessicaherman/vrx-competitor-example:2023.v2 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,64 @@ | ||
wamv_camera: | ||
- name: front_left_camera | ||
visualize: False | ||
x: 0.75 | ||
y: 0.1 | ||
z: 1.5 | ||
R: 0.0 | ||
P: ${radians(15)} | ||
Y: 0.0 | ||
post_Y: 0.0 | ||
- name: front_right_camera | ||
visualize: False | ||
x: 0.75 | ||
y: -0.1 | ||
z: 1.5 | ||
R: 0.0 | ||
P: ${radians(15)} | ||
Y: 0.0 | ||
post_Y: 0.0 | ||
- name: far_left_camera | ||
visualize: False | ||
x: 0.75 | ||
y: 0.3 | ||
z: 1.5 | ||
R: 0.0 | ||
P: ${radians(15)} | ||
Y: 0.0 | ||
post_Y: 0.0 | ||
wamv_gps: | ||
- name: gps_wamv | ||
x: -0.85 | ||
y: 0.0 | ||
z: 1.3 | ||
R: 0.0 | ||
P: 0.0 | ||
Y: 0.0 | ||
wamv_imu: | ||
- name: imu_wamv | ||
x: 0.3 | ||
y: -0.2 | ||
z: 1.3 | ||
R: 0.0 | ||
P: 0.0 | ||
Y: 0.0 | ||
lidar: | ||
- name: lidar_wamv | ||
type: 16_beam | ||
x: 0.7 | ||
y: 0.0 | ||
z: 1.8 | ||
R: 0.0 | ||
P: ${radians(8)} | ||
Y: 0.0 | ||
post_Y: 0.0 | ||
wamv_ball_shooter: | ||
- name: ball_shooter | ||
x: 0.55 | ||
y: -0.3 | ||
z: 1.3 | ||
pitch: ${radians(-20)} | ||
yaw: 0.0 | ||
wamv_pinger: | ||
- name: pinger | ||
position: 1.0 0 -1.0 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1 @@ | ||
crvogt/vrx_2022_simple |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
engine: | ||
- prefix: "left" | ||
position: "-2.373776 1.027135 0.318237" | ||
orientation: "0.0 0.0 0.0" | ||
- prefix: "right" | ||
position: "-2.373776 -1.027135 0.318237" | ||
orientation: "0.0 0.0 0.0" | ||
- prefix: "middle" | ||
position: "0 0 0.318237" | ||
orientation: "0.0 0.0 0.0" |
Oops, something went wrong.