all_seaing_driver - ArcturusNavigation/all_seaing_vehicle GitHub Wiki

Back: Documentation

Launch Files

32e_points.launch.py

Launches the HDL-32E Velodyne LiDAR. The point cloud is attached to the /velodyne frame.

mavros.launch.py

Launches the MAVROS node to connect to the PixHawk.

zed2i.launch.py

Launches the ZED2i nodes to connect to the ZED2i camera. This is equivalent to ros2 launch zed_wrapper zed_camera.launch.py camera_model:=zed2i.

oak.launch.py

Launches the nodes for the interface of the back left and back right Oak cameras with ROS.

Nodes

thrust_commander.py

Node to receive thrust values and send it to the PixHawk.

Subscribed topics:

  • thrusters/front_left/thrust, thrusters/front_right/thrust, thrusters/back_left/thrust, thrusters/back_right/thrust: std_msgs/Int64 messages with thruster PWM commands.

Parameters:

  • front_right_port, front_left_port, back_right_port, back_left_port: integer parameters defaulting to 2, 3, 4, and 5 respectively. The port where the thrusters are attached to on the PixHawk.

Client:

webcam_publisher.py

Node to publish the webcam image

Published topics:

zed2i_publisher.py

Node to publish an image from the ZED camera without the ZED SDK.

Published topics:

odometry_publisher.py

A node that combines positional data from the GPS topic (fused or raw) and velocity & orientation from an odometry topic, converts the GPS coordinates to a local cartesian frame (using a UTM projection) given a (lat, lon, heading) datum, and publishes the odom->base_link transform in the TF tree and an odometry message with the combined data.

Subscribed topics:

  • gps_topic (to be remapped): a NavSatFix message containing the GPS positional data
  • odom_topic (to be remapped): an Odometry message containing the velocities & orientation data
  • pos_odom_topic (to be remapped): an Odometry message containing positional data in a cartesian frame, if we want to use that instead of converting GPS coordinates (for example in case of another node fusing the GPS data with other odometry, the Pixhawk providing fused coordinates in a cartesian frame already, in mavros/local_position/odom)

Published topics:

  • odometry/gps: an Odometry containing the combined positional and velocity + orientation data from the respective topics

Parameters:

  • global_frame_id: the global frame that the positional data is mapped to, defaults to odom
  • base_link_frame: the robot's frame that acts as base_link (possibly also gps_link or imu_link to take into account the offset from the LiDAR, which is currently base_link), defaults to base_link
  • datum: the latitude, longitude, and heading (0 being East) that will be the origin of the cartesian frame that the robot's position will be computed in, using the GPS coordinates, defaults to [42.3567949, -71.1070491, 0.0] (Sea Grant coordinates)
  • yaw_offset: the offset angle of the Pixhawk (whose compass hopefully gives a 0 value when facing East in the odom message) wrt to the front of the robot, or the offset of the Pixhawk's 0 compass value wrt to East, defaults to pi/2 (90 degrees to the left of the robot, might change)
  • odom_yaw_offset: hopefully the same as yaw_offset, the offset angle by which the odometry data needs to be transformed to make the x velocities large positive when the robot is going forwards, and the y velocities when going left, respectively, defaults to pi/2 (90 degrees to the left of the robot, might change)
  • use_odom_pos: whether to use pos_odom_topic for position or the GPS as intended, defaults to True
  • utm_zone: the UTM zone to use for the GPS->cartesian conversion, Boston is zone 19N, Florida (Sarasota, at least) is 17N, defaults to 19

central_hub_ros.py

The node that interfaces with the central hub, using the firmware in ArcturusEE.py. Accepts command_adj (CommandAdj), command_servo (CommandServo), get_estop_status (GetEstopStatus), and command_fan (CommandServo) service calls.

Parameters:

  • port: the port the central hub is in, may change after Jetson reboot or connecting/disconnecting devices, defaults to /dev/ttyACM0

rover_custom_controller.py

The node that requests the EStop status and joystick values from central_hub_ros.py and sends them to ROS.

Published topics:

  • control_options: a ControlOption message, consisting of a velocity and a priority, that's sent to control_mux.py, to move the thrusters
  • heartbeat: a Heartbeat message including the teleop (manual vs auto) and EStop status
  • keyboard_button: a topic used to start tasks (originated from sim) and transition between them, essentially the teleop status

Parameters:

  • joy_x_scale: scaling of the x axis of the joystick (to limit forward speed when manually driving the boat)
  • joy_ang_scale: scaling of the y axis of the joystick (to limit turning speed when manually driving the boat)