Package Summary
Documented
Package to store all code relating to the control of OSU's AUV.
- Maintainer status: maintained
- Maintainer: OSU UWRT <osu.uwrt AT gmail DOT com>
- Author: Blaine Miller, Mitchell Sayre
- License: BSD
- Source: git https://github.com/osu-uwrt/riptide_controllers.git (branch: dev)
Contents
Nodes
controller
Main controller for the OSU AUV. This node is made up of 2 cascaded P controllers. One for linear and one for angular control. They are independent of each other and each can be in one of the following states:1. Disabled: The controller is not requesting any action.
2. Velocity: The controller is trying to hold a target velocity.
3. Position: The controller is trying to hold a target position or orientation.
4. Trajectory: The controller is trying to follow a given trajectory
Note: Even when both controllers are in the disabled state, the thrusters will still turn to counteract buoyancy and drag. If you want the thrusters to stop, publish to the "off" topic or pull the kill switch.
Action Goal
follow_trajectory (riptide_controllers/FollowTrajectoryAction)- Will set both controllers to trajectory mode and execute the given trajectory.
Subscribed Topics
odometry/filtered (nav_msgs/Odometry)- The current state of the vehicle.
- Whether the kill switch is pulled. When pulled, will disable both controllers and stop the thrusters.
- Puts the linear controller in position mode and sets the target to the given position.
- Puts the linear controller in velocity mode and sets the target to the given velocity.
- Puts the linear controller in the disabled state.
- Puts the angular controller in position mode and sets the target to the given orientation.
- Puts the angular controller in velocity mode and sets the target to the given velocity.
- Puts the angular controller in the disabled state.
- Puts both controllers in the disabled state and then stops the thrusters.
Published Topics
net_force (geometry_msgs/Twist)- Forces and torques the vehicle should be exerting on the water to satisfy the controllers.
- Whether the controllers have achieved their targets.
- The acceleration the vehicle should experience after requesting the force. Used for calibration.
Parameters
~vehicle_config (string)- Path to the vehicle's description yaml file.
thruster_solver
This node takes the requested force and torque from the controller and converts it into thruster forces. It will find the optimal thruster force combination that uses the least amount of power while only using thrusters that are completely submerged.Subscribed Topics
net_force (geometry_msgs/Twist)- The force and torque the controller requested.
Published Topics
thruster_forces (std_msgs/Float32MultiArray)- The forces each thruster should exert.
- The PWM values which should be applied to the thrusters.
Parameters
~vehicle_config (string)- Path to the vehicle's description yaml file.