Public Member Functions | Public Attributes | Protected Attributes | List of all members
gazebo::Thruster Class Reference

Thruster class. More...

#include <usv_gazebo_thrust_plugin.hh>

Public Member Functions

void OnThrustAngle (const std_msgs::Float32::ConstPtr &_msg)
 Callback for new thrust angle commands. More...
 
void OnThrustCmd (const std_msgs::Float32::ConstPtr &_msg)
 Callback for new thrust commands. More...
 
 Thruster (UsvThrust *_parent)
 Constructor. More...
 

Public Attributes

ros::Subscriber angleSub
 Subscription to thruster commands. More...
 
std::string angleTopic
 Topic name for incoming ROS thruster angle commands. More...
 
ros::Subscriber cmdSub
 Subscription to thruster commands. More...
 
std::string cmdTopic
 Topic name for incoming ROS thruster commands. More...
 
double currCmd
 Current, most recent command. More...
 
double desiredAngle
 Most recent desired angle. More...
 
bool enableAngle
 If true, thruster will have adjustable angle. If false, thruster will have constant angle. More...
 
physics::JointPtr engineJoint
 Joint controlling the engine. More...
 
common::PID engineJointPID
 PID for engine joint angle. More...
 
common::Time lastAngleUpdateTime
 Last time of update. More...
 
common::Time lastCmdTime
 Last time received a command via ROS topic. More...
 
physics::LinkPtr link
 Link where thrust force is applied. More...
 
int mappingType
 Thruster mapping (0=linear; 1=GLF, nonlinear). More...
 
double maxAngle
 Maximum abs val of angle. More...
 
double maxCmd
 Maximum abs val of incoming command. More...
 
double maxForceFwd
 Max forward force in Newtons. More...
 
double maxForceRev
 Max reverse force in Newtons. More...
 
physics::JointPtr propJoint
 Joint controlling the propeller. More...
 

Protected Attributes

UsvThrustplugin
 Plugin parent pointer - for accessing world, etc. More...
 

Detailed Description

Thruster class.

Definition at line 40 of file usv_gazebo_thrust_plugin.hh.

Constructor & Destructor Documentation

Thruster::Thruster ( UsvThrust _parent)
explicit

Constructor.

Parameters
[in]_parentPointer to an SDF element to parse.

Definition at line 29 of file usv_gazebo_thrust_plugin.cc.

Member Function Documentation

void Thruster::OnThrustAngle ( const std_msgs::Float32::ConstPtr &  _msg)

Callback for new thrust angle commands.

Parameters
[in]_msgThe thrust angle message to process.

Definition at line 59 of file usv_gazebo_thrust_plugin.cc.

void Thruster::OnThrustCmd ( const std_msgs::Float32::ConstPtr &  _msg)

Callback for new thrust commands.

Parameters
[in]_msgThe thrust message to process.

Definition at line 45 of file usv_gazebo_thrust_plugin.cc.

Member Data Documentation

ros::Subscriber gazebo::Thruster::angleSub

Subscription to thruster commands.

Definition at line 86 of file usv_gazebo_thrust_plugin.hh.

std::string gazebo::Thruster::angleTopic

Topic name for incoming ROS thruster angle commands.

Definition at line 83 of file usv_gazebo_thrust_plugin.hh.

ros::Subscriber gazebo::Thruster::cmdSub

Subscription to thruster commands.

Definition at line 76 of file usv_gazebo_thrust_plugin.hh.

std::string gazebo::Thruster::cmdTopic

Topic name for incoming ROS thruster commands.

Definition at line 73 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::currCmd

Current, most recent command.

Definition at line 89 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::desiredAngle

Most recent desired angle.

Definition at line 92 of file usv_gazebo_thrust_plugin.hh.

bool gazebo::Thruster::enableAngle

If true, thruster will have adjustable angle. If false, thruster will have constant angle.

Definition at line 80 of file usv_gazebo_thrust_plugin.hh.

physics::JointPtr gazebo::Thruster::engineJoint

Joint controlling the engine.

Definition at line 104 of file usv_gazebo_thrust_plugin.hh.

common::PID gazebo::Thruster::engineJointPID

PID for engine joint angle.

Definition at line 107 of file usv_gazebo_thrust_plugin.hh.

common::Time gazebo::Thruster::lastAngleUpdateTime

Last time of update.

Definition at line 98 of file usv_gazebo_thrust_plugin.hh.

common::Time gazebo::Thruster::lastCmdTime

Last time received a command via ROS topic.

Definition at line 95 of file usv_gazebo_thrust_plugin.hh.

physics::LinkPtr gazebo::Thruster::link

Link where thrust force is applied.

Definition at line 67 of file usv_gazebo_thrust_plugin.hh.

int gazebo::Thruster::mappingType

Thruster mapping (0=linear; 1=GLF, nonlinear).

Definition at line 70 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::maxAngle

Maximum abs val of angle.

Definition at line 64 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::maxCmd

Maximum abs val of incoming command.

Definition at line 55 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::maxForceFwd

Max forward force in Newtons.

Definition at line 58 of file usv_gazebo_thrust_plugin.hh.

double gazebo::Thruster::maxForceRev

Max reverse force in Newtons.

Definition at line 61 of file usv_gazebo_thrust_plugin.hh.

UsvThrust* gazebo::Thruster::plugin
protected

Plugin parent pointer - for accessing world, etc.

Definition at line 110 of file usv_gazebo_thrust_plugin.hh.

physics::JointPtr gazebo::Thruster::propJoint

Joint controlling the propeller.

Definition at line 101 of file usv_gazebo_thrust_plugin.hh.


The documentation for this class was generated from the following files:


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:47