
Public Member Functions | |
| def | __init__ (self, args) |
| def | get_pid_params_callback (self, request) |
| def | set_pid_params_callback (self, request) |
| def | update_controller (self) |
Public Member Functions inherited from uuv_control_interfaces.dp_controller_base.DPControllerBase | |
| 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) |
Private Member Functions | |
| def | _reset_controller (self) |
Private Attributes | |
| _error_pose | |
| _int | |
| _is_init | |
| _Kd | |
| _Ki | |
| _Kp | |
| _tau | |
Additional Inherited Members | |
Static Public Member Functions inherited from uuv_control_interfaces.dp_controller_base.DPControllerBase | |
| def | get_controller (name, args) |
| def | get_list_of_controllers () |
Public Attributes inherited from uuv_control_interfaces.dp_controller_base.DPControllerBase | |
| thrusters_only | |
| use_auv_control_allocator | |
This is an abstract class for PID-based controllers. The base class method update_controller must be overridden in other for a controller to work.
Definition at line 22 of file rov_ua_pid_controller.py.
| def rov_ua_pid_controller.ROVUnderActuatedPIDController.__init__ | ( | self, | |
| args | |||
| ) |
Definition at line 28 of file rov_ua_pid_controller.py.
|
private |
Definition at line 85 of file rov_ua_pid_controller.py.
| def rov_ua_pid_controller.ROVUnderActuatedPIDController.get_pid_params_callback | ( | self, | |
| request | |||
| ) |
Definition at line 101 of file rov_ua_pid_controller.py.
| def rov_ua_pid_controller.ROVUnderActuatedPIDController.set_pid_params_callback | ( | self, | |
| request | |||
| ) |
Definition at line 90 of file rov_ua_pid_controller.py.
| def rov_ua_pid_controller.ROVUnderActuatedPIDController.update_controller | ( | self | ) |
Definition at line 107 of file rov_ua_pid_controller.py.
|
private |
Definition at line 41 of file rov_ua_pid_controller.py.
|
private |
Definition at line 39 of file rov_ua_pid_controller.py.
|
private |
Definition at line 82 of file rov_ua_pid_controller.py.
|
private |
Definition at line 35 of file rov_ua_pid_controller.py.
|
private |
Definition at line 37 of file rov_ua_pid_controller.py.
|
private |
Definition at line 33 of file rov_ua_pid_controller.py.
|
private |
Definition at line 127 of file rov_ua_pid_controller.py.