Public Member Functions | Private Attributes | List of all members
uuv_simulator_ros::ThrusterROSPlugin Class Reference

#include <ThrusterROSPlugin.hh>

Inheritance diagram for uuv_simulator_ros::ThrusterROSPlugin:
Inheritance graph
[legend]

Public Member Functions

bool GetDynamicStateEfficiency (uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Request &_req, uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Response &_res)
 Get the dynamic state efficiency factor. More...
 
gazebo::common::Time GetRosPublishPeriod ()
 Return the ROS publish period. More...
 
bool GetThrusterConversionFcn (uuv_gazebo_ros_plugins_msgs::GetThrusterConversionFcn::Request &_req, uuv_gazebo_ros_plugins_msgs::GetThrusterConversionFcn::Response &_res)
 Get thruster conversion function parameters. More...
 
bool GetThrusterState (uuv_gazebo_ros_plugins_msgs::GetThrusterState::Request &_req, uuv_gazebo_ros_plugins_msgs::GetThrusterState::Response &_res)
 Get thruster state. More...
 
bool GetThrustForceEfficiency (uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Request &_req, uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Response &_res)
 Get the thrust efficiency factor. More...
 
virtual void Init ()
 Initialize Module. More...
 
void Load (gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load module and read parameters from SDF. More...
 
virtual void Reset ()
 Reset Module. More...
 
void RosPublishStates ()
 Publish thruster state via ROS. More...
 
bool SetDynamicStateEfficiency (uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Request &_req, uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Response &_res)
 Set the dynamic state efficiency factor. More...
 
void SetRosPublishRate (double _hz)
 Set the ROS publish frequency (Hz). More...
 
bool SetThrusterState (uuv_gazebo_ros_plugins_msgs::SetThrusterState::Request &_req, uuv_gazebo_ros_plugins_msgs::SetThrusterState::Response &_res)
 Turn thruster on/off. More...
 
bool SetThrustForceEfficiency (uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Request &_req, uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Response &_res)
 Set the thrust efficiency factor. More...
 
void SetThrustReference (const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg)
 Set new set point (desired thrust [N]) for thruster. More...
 
 ThrusterROSPlugin ()
 Constrcutor. More...
 
 ~ThrusterROSPlugin ()
 Destructor. More...
 
- Public Member Functions inherited from gazebo::ThrusterPlugin
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
 ThrusterPlugin ()
 
void Update (const common::UpdateInfo &_info)
 
virtual ~ThrusterPlugin ()
 

Private Attributes

gazebo::common::Time lastRosPublishTime
 Last time we published a message via ROS. More...
 
ros::Publisher pubDynamicStateEff
 Publisher for the dynamic state efficiency. More...
 
ros::Publisher pubThrust
 Publisher for current actual thrust. More...
 
ros::Publisher pubThrusterState
 Publisher for the thruster state. More...
 
ros::Publisher pubThrustForceEff
 Publisher for the thrust force efficiency. More...
 
ros::Publisher pubThrustWrench
 Publisher for current actual thrust as wrench. More...
 
boost::scoped_ptr< ros::NodeHandlerosNode
 Pointer to this ROS node's handle. More...
 
gazebo::event::ConnectionPtr rosPublishConnection
 Connection for callbacks on update world. More...
 
gazebo::common::Time rosPublishPeriod
 Period after which we should publish a message via ROS. More...
 
std::map< std::string, ros::ServiceServerservices
 Map of thruster services. More...
 
ros::Subscriber subThrustReference
 Subscriber reacting to new reference thrust set points. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gazebo::ThrusterPlugin
void UpdateInput (ConstDoublePtr &_msg)
 
- Protected Attributes inherited from gazebo::ThrusterPlugin
double clampMax
 
double clampMin
 
transport::SubscriberPtr commandSubscriber
 
std::shared_ptr< ConversionFunctionconversionFunction
 
double gain
 
double inputCommand
 
bool isOn
 
physics::JointPtr joint
 
transport::NodePtr node
 
double propellerEfficiency
 
double thrustEfficiency
 
ignition::math::Vector3d thrusterAxis
 
std::shared_ptr< DynamicsthrusterDynamics
 
int thrusterID
 
physics::LinkPtr thrusterLink
 
double thrustForce
 
common::Time thrustForceStamp
 
double thrustMax
 
double thrustMin
 
transport::PublisherPtr thrustTopicPublisher
 
std::string topicPrefix
 
event::ConnectionPtr updateConnection
 

Detailed Description

Definition at line 41 of file ThrusterROSPlugin.hh.

Constructor & Destructor Documentation

uuv_simulator_ros::ThrusterROSPlugin::ThrusterROSPlugin ( )

Constrcutor.

Definition at line 30 of file ThrusterROSPlugin.cc.

uuv_simulator_ros::ThrusterROSPlugin::~ThrusterROSPlugin ( )

Destructor.

Definition at line 37 of file ThrusterROSPlugin.cc.

Member Function Documentation

bool uuv_simulator_ros::ThrusterROSPlugin::GetDynamicStateEfficiency ( uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Request &  _req,
uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Response &  _res 
)

Get the dynamic state efficiency factor.

Definition at line 275 of file ThrusterROSPlugin.cc.

gazebo::common::Time uuv_simulator_ros::ThrusterROSPlugin::GetRosPublishPeriod ( )

Return the ROS publish period.

Definition at line 63 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::GetThrusterConversionFcn ( uuv_gazebo_ros_plugins_msgs::GetThrusterConversionFcn::Request &  _req,
uuv_gazebo_ros_plugins_msgs::GetThrusterConversionFcn::Response &  _res 
)

Get thruster conversion function parameters.

Definition at line 305 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::GetThrusterState ( uuv_gazebo_ros_plugins_msgs::GetThrusterState::Request &  _req,
uuv_gazebo_ros_plugins_msgs::GetThrusterState::Response &  _res 
)

Get thruster state.

Definition at line 296 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::GetThrustForceEfficiency ( uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Request &  _req,
uuv_gazebo_ros_plugins_msgs::GetThrusterEfficiency::Response &  _res 
)

Get the thrust efficiency factor.

Definition at line 246 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::Init ( )
virtual

Initialize Module.

Reimplemented from gazebo::ThrusterPlugin.

Definition at line 78 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::Load ( gazebo::physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load module and read parameters from SDF.

Definition at line 90 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::Reset ( )
virtual

Reset Module.

Reimplemented from gazebo::ThrusterPlugin.

Definition at line 84 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::RosPublishStates ( )

Publish thruster state via ROS.

Definition at line 183 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::SetDynamicStateEfficiency ( uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Request &  _req,
uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Response &  _res 
)

Set the dynamic state efficiency factor.

Definition at line 255 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::SetRosPublishRate ( double  _hz)

Set the ROS publish frequency (Hz).

Definition at line 69 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::SetThrusterState ( uuv_gazebo_ros_plugins_msgs::SetThrusterState::Request &  _req,
uuv_gazebo_ros_plugins_msgs::SetThrusterState::Response &  _res 
)

Turn thruster on/off.

Definition at line 284 of file ThrusterROSPlugin.cc.

bool uuv_simulator_ros::ThrusterROSPlugin::SetThrustForceEfficiency ( uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Request &  _req,
uuv_gazebo_ros_plugins_msgs::SetThrusterEfficiency::Response &  _res 
)

Set the thrust efficiency factor.

Definition at line 226 of file ThrusterROSPlugin.cc.

void uuv_simulator_ros::ThrusterROSPlugin::SetThrustReference ( const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &  _msg)

Set new set point (desired thrust [N]) for thruster.

Definition at line 50 of file ThrusterROSPlugin.cc.

Member Data Documentation

gazebo::common::Time uuv_simulator_ros::ThrusterROSPlugin::lastRosPublishTime
private

Last time we published a message via ROS.

Definition at line 137 of file ThrusterROSPlugin.hh.

ros::Publisher uuv_simulator_ros::ThrusterROSPlugin::pubDynamicStateEff
private

Publisher for the dynamic state efficiency.

Definition at line 128 of file ThrusterROSPlugin.hh.

ros::Publisher uuv_simulator_ros::ThrusterROSPlugin::pubThrust
private

Publisher for current actual thrust.

Definition at line 116 of file ThrusterROSPlugin.hh.

ros::Publisher uuv_simulator_ros::ThrusterROSPlugin::pubThrusterState
private

Publisher for the thruster state.

Definition at line 122 of file ThrusterROSPlugin.hh.

ros::Publisher uuv_simulator_ros::ThrusterROSPlugin::pubThrustForceEff
private

Publisher for the thrust force efficiency.

Definition at line 125 of file ThrusterROSPlugin.hh.

ros::Publisher uuv_simulator_ros::ThrusterROSPlugin::pubThrustWrench
private

Publisher for current actual thrust as wrench.

Definition at line 119 of file ThrusterROSPlugin.hh.

boost::scoped_ptr<ros::NodeHandle> uuv_simulator_ros::ThrusterROSPlugin::rosNode
private

Pointer to this ROS node's handle.

Definition at line 110 of file ThrusterROSPlugin.hh.

gazebo::event::ConnectionPtr uuv_simulator_ros::ThrusterROSPlugin::rosPublishConnection
private

Connection for callbacks on update world.

Definition at line 131 of file ThrusterROSPlugin.hh.

gazebo::common::Time uuv_simulator_ros::ThrusterROSPlugin::rosPublishPeriod
private

Period after which we should publish a message via ROS.

Definition at line 134 of file ThrusterROSPlugin.hh.

std::map<std::string, ros::ServiceServer> uuv_simulator_ros::ThrusterROSPlugin::services
private

Map of thruster services.

Definition at line 107 of file ThrusterROSPlugin.hh.

ros::Subscriber uuv_simulator_ros::ThrusterROSPlugin::subThrustReference
private

Subscriber reacting to new reference thrust set points.

Definition at line 113 of file ThrusterROSPlugin.hh.


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


uuv_gazebo_ros_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:28