Public Member Functions | |
def | __del__ (self) |
def | __init__ (self, is_model_based=False, list_odometry_callbacks=None, planner_full_dof=False) |
def | __str__ (self) |
def | error_orientation_quat (self) |
def | error_orientation_rpy (self) |
def | error_pos_world (self) |
def | error_pose_euler (self) |
def | error_vel_world (self) |
def | label (self) |
def | odom_is_init (self) |
def | publish_auv_command (self, surge_speed, wrench) |
def | publish_control_wrench (self, force) |
def | reset_controller_callback (self, request) |
def | update_controller (self) |
def | update_errors (self) |
Static Public Member Functions | |
def | get_controller (name, args) |
def | get_list_of_controllers () |
Public Attributes | |
thrusters_only | |
use_auv_control_allocator | |
Private Member Functions | |
def | _create_vehicle_model (self) |
def | _odometry_callback (self, msg) |
def | _reset_controller (self) |
def | _update_reference (self) |
def | _update_time_step (self) |
Static Private Attributes | |
string | _LABEL = '' |
General abstract class for DP controllers for underwater vehicles. This is an abstract class, must be inherited by a controller module that overrides the update_controller method. If the controller is set to be model based (is_model_based=True), than the vehicle parameters are going to be read from the ROS parameter server. > *Input arguments* * `is_model_based` (*type:* `bool`, *default:* `False`): If `True`, the controller uses a model of the vehicle, `False` if it is non-model-based. * `list_odometry_callbacks` (*type:* `list`, *default:* `None`): List of function handles or `lambda` functions that will be called after each odometry update. * `planner_full_dof` (*type:* `bool`, *default:* `False`): Set the local planner to generate 6 DoF trajectories. Otherwise, the planner will only generate 4 DoF trajectories `(x, y, z, yaw)`. > *ROS parameters* * `use_stamped_poses_only` (*type:* `bool`, *default:* `False`): If `True`, the reference path will be generated with stamped poses only, velocity and acceleration references are set to zero. * `thrusters_only` (*type:* `bool`, *default:* `True`): If `True`, the vehicle only has thrusters as actuators and a thruster manager node is running and the control output will be published as `geometry_msgs/WrenchStamped`. If `False`, the AUV force allocation should be used to compute the control output for each actuator and the output control will be generated as a `uuv_auv_control_allocator.AUVCommand` message. * `saturation` (*type:* `float`, *default:* `5000`): Absolute saturation of the control signal. * `use_auv_control_allocator` (*type:* `bool`, *default:* `False`): If `True`, the output control will be `AUVCommand` message. * `min_thrust` (*type:* `float`, *default:* `40`): Min. thrust set-point output, (parameter only valid for AUVs). > *ROS publishers* * `thruster_output` (*message:* `geometry_msgs/WrenchStamped`): Control set-point for the thruster manager node (requirement: ROS parameters must be `thrusters_only` must be set as `True` and a thruster manager from `uuv_thruster_manager` node must be running). * `auv_command_output` (*message:* `uuv_auv_control_allocator.AUVCommand`): Control set-point for the AUV allocation node (requirement: ROS parameters must be `thrusters_only` must be set as `False` and a AUV control allocation node from `uuv_auv_control_allocator` node must be running). * `reference` (*message:* `uuv_control_msgs/TrajectoryPoint`): Current reference trajectory point. * `error` (*message:* `uuv_control_msgs/TrajectoryPoint`): Current trajectory error. > *ROS services* * `reset_controller` (*service:* `uuv_control_msgs/ResetController`): Reset all variables, including error and reference signals.
Definition at line 39 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.__init__ | ( | self, | |
is_model_based = False , |
|||
list_odometry_callbacks = None , |
|||
planner_full_dof = False |
|||
) |
Definition at line 98 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.__del__ | ( | self | ) |
Definition at line 212 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.__str__ | ( | self | ) |
Definition at line 286 of file dp_controller_base.py.
|
private |
Create a new instance of a vehicle model. If controller is not model based, this model will have its parameters set to 0 and will be used to receive and transform the odometry data.
Definition at line 293 of file dp_controller_base.py.
|
private |
Odometry topic subscriber callback function. > *Input arguments* * `msg` (*type:* `nav_msgs/Odometry`): Input odometry message
Definition at line 469 of file dp_controller_base.py.
|
private |
Reset reference and and error vectors.
Definition at line 339 of file dp_controller_base.py.
|
private |
Call the local planner interpolator to retrieve a trajectory point and publish the reference message as `uuv_control_msgs/TrajectoryPoint`.
Definition at line 303 of file dp_controller_base.py.
|
private |
Update time step.
Definition at line 333 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.error_orientation_quat | ( | self | ) |
`numpy.array`: Orientation error
Definition at line 247 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.error_orientation_rpy | ( | self | ) |
`numpy.array`: Orientation error in Euler angles.
Definition at line 252 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.error_pos_world | ( | self | ) |
`numpy.array`: Position error wrt world frame
Definition at line 242 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.error_pose_euler | ( | self | ) |
`numpy.array`: Pose error with orientation represented in Euler angles.
Definition at line 277 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.error_vel_world | ( | self | ) |
`numpy.array`: Linear velocity error
Definition at line 282 of file dp_controller_base.py.
|
static |
Create instance of a specific DP controller.
Definition at line 218 of file dp_controller_base.py.
|
static |
Return list of DP controllers using this interface.
Definition at line 226 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.label | ( | self | ) |
`str`: Identifier name of the controller
Definition at line 232 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.odom_is_init | ( | self | ) |
`bool`: `True` if the first odometry message was received
Definition at line 237 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.publish_auv_command | ( | self, | |
surge_speed, | |||
wrench | |||
) |
Publish the AUV control command message > *Input arguments* * `surge_speed` (*type:* `float`): Reference surge speed * `wrench` (*type:* `numpy.array`): 6 DoF wrench vector
Definition at line 443 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.publish_control_wrench | ( | self, | |
force | |||
) |
Publish the thruster manager control set-point. > *Input arguments* * `force` (*type:* `numpy.array`): 6 DoF control set-point wrench vector
Definition at line 407 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.reset_controller_callback | ( | self, | |
request | |||
) |
Service handler function.
Definition at line 354 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.update_controller | ( | self | ) |
This function must be implemented by derived classes with the implementation of the control algorithm.
Definition at line 359 of file dp_controller_base.py.
def uuv_control_interfaces.dp_controller_base.DPControllerBase.update_errors | ( | self | ) |
Update error vectors.
Definition at line 366 of file dp_controller_base.py.
|
private |
Definition at line 151 of file dp_controller_base.py.
|
private |
Definition at line 128 of file dp_controller_base.py.
|
private |
Definition at line 179 of file dp_controller_base.py.
|
private |
Definition at line 162 of file dp_controller_base.py.
|
private |
Definition at line 174 of file dp_controller_base.py.
|
private |
Definition at line 202 of file dp_controller_base.py.
|
private |
Definition at line 165 of file dp_controller_base.py.
|
private |
Definition at line 100 of file dp_controller_base.py.
|
private |
Definition at line 107 of file dp_controller_base.py.
|
staticprivate |
Definition at line 95 of file dp_controller_base.py.
|
private |
Definition at line 123 of file dp_controller_base.py.
|
private |
Definition at line 101 of file dp_controller_base.py.
|
private |
Definition at line 156 of file dp_controller_base.py.
|
private |
Definition at line 104 of file dp_controller_base.py.
|
private |
Definition at line 205 of file dp_controller_base.py.
|
private |
Definition at line 195 of file dp_controller_base.py.
|
private |
Definition at line 209 of file dp_controller_base.py.
|
private |
Definition at line 180 of file dp_controller_base.py.
|
private |
Definition at line 168 of file dp_controller_base.py.
|
private |
Definition at line 158 of file dp_controller_base.py.
|
private |
Definition at line 182 of file dp_controller_base.py.
|
private |
Definition at line 188 of file dp_controller_base.py.
|
private |
Definition at line 145 of file dp_controller_base.py.
|
private |
Definition at line 131 of file dp_controller_base.py.
|
private |
Definition at line 114 of file dp_controller_base.py.
|
private |
Definition at line 191 of file dp_controller_base.py.
uuv_control_interfaces.dp_controller_base.DPControllerBase.thrusters_only |
Definition at line 120 of file dp_controller_base.py.
uuv_control_interfaces.dp_controller_base.DPControllerBase.use_auv_control_allocator |
Definition at line 137 of file dp_controller_base.py.