all_seaing_controller - ArcturusNavigation/all_seaing_vehicle GitHub Wiki
| Back: Documentation |
|---|
Nodes
control_mux.py
Selects the highest priority (lowest priority value) control_options and publish as control_input
Subscribed topics:
control_options: an all_seaing_interfaces/ControlMessage message with all the options for the control input.
Published topics:
cmd_vel: a geometry_msgs/Twist message with the chosen control input.
controller_server.py
Hosts ROS action servers for controlling the boat (e.g waypoint following) with an internal PID controller.
Subscribed topics:
odometry/filtered: a nav_msgs/Odometry message containing the (filtered) robot odometry.
Published topics:
control_options: an all_seaing_interfaces/ControlOption message which contains the desired robot twist.control_marker: a visualization_msgs/Marker message for visualization.
Parameters:
global_frame_id: string parameter. Specifies the id of the global frame. Defaults toodom.Kpid_x,Kpid_y,Kpid_theta: double array parameters.[Kp, Ki, Kd]values for the robot's x, y, theta movements.max_vel: double array parameter. The desired maximum[x, y, theta]velocities of the robot.
Action servers:
waypoint: an all_seaing_interfaces/Waypoint action server for following the requested[x, y, theta]values. The theta value can be ignored ifignore_theta = True. Thethresholdvalues determine how close the robot must be to the target[x, y, theta]for the service to be completed.
xdrive_controller.py
Converts the cmd_vel Twist message to thruster values based on the boat's dimensions and the center of mass. See here for the detailed math.
Subscribed topics:
cmd_vel: a geometry_msgs/Twist message with the robot's velocity.
Published topics:
thrusters/front_left/thrust,thrusters/front_right/thrust,thrusters/back_left/thrust,thrusters/back_right/thrust: std_msgs/Float64 messages to send thruster PWM commands.
Parameters:
front_right_xy,back_left_xy,front_left_xy,back_right_xy: double array parameters. The[x, y]coordinates of each thruster. The positivexdirection corresponds to the "forward" direction and the positiveydirection corresponds to the "left" direction.thruster_angle: double parameter. Angle of the thrusters in degrees (e.g. 60 if facing 15 degrees "more forward").drag_constants: double array parameter. The empirically determined[x, y, theta]constants representing the value $\frac{1}{2}\rho c_dA$ where $\rho$ is the fluid density, $c_d$ is the drag coefficient, and $A$ is the reference area.output_range: double array parameter. The[min, max]range of the output thruster values (e.g.[1100, 1900]for the pixhawk PWM range).smoothing_factor: double parameter. Let this value be $\alpha$. Then, $x_n\leftarrow\alpha x_{n-1}+(1-\alpha) x_n$ where $x_n$ is the thrust output at timestep $n$.