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

#include <FinROSPlugin.hh>

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

Public Member Functions

 FinROSPlugin ()
 Constrcutor. More...
 
bool GetLiftDragParams (uuv_gazebo_ros_plugins_msgs::GetListParam::Request &_req, uuv_gazebo_ros_plugins_msgs::GetListParam::Response &_res)
 Return the list of paramaters of the lift and drag model. More...
 
gazebo::common::Time GetRosPublishPeriod ()
 Return the ROS publish period. 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 state via ROS. More...
 
void SetReference (const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg)
 Set new set point. More...
 
void SetRosPublishRate (double _hz)
 Set the ROS publish frequency (Hz). More...
 
 ~FinROSPlugin ()
 Destructor. More...
 
- Public Member Functions inherited from gazebo::FinPlugin
 FinPlugin ()
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
void OnUpdate (const common::UpdateInfo &_info)
 
virtual ~FinPlugin ()
 

Private Attributes

gazebo::common::Time lastRosPublishTime
 Last time we published a message via ROS. More...
 
ros::Publisher pubFinForce
 Publisher for current actual thrust. More...
 
ros::Publisher pubState
 Publisher for current state. 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 services. More...
 
ros::Subscriber subReference
 Subscriber reacting to new reference set points. More...
 

Additional Inherited Members

- Protected Member Functions inherited from gazebo::FinPlugin
void UpdateCurrentVelocity (ConstVector3dPtr &_msg)
 
void UpdateInput (ConstDoublePtr &_msg)
 
- Protected Attributes inherited from gazebo::FinPlugin
double angle
 
transport::PublisherPtr anglePublisher
 
common::Time angleStamp
 
transport::SubscriberPtr commandSubscriber
 
transport::SubscriberPtr currentSubscriber
 
ignition::math::Vector3d currentVelocity
 
std::shared_ptr< Dynamicsdynamics
 
ignition::math::Vector3d finForce
 
int finID
 
double inputCommand
 
physics::JointPtr joint
 
std::shared_ptr< LiftDragliftdrag
 
physics::LinkPtr link
 
transport::NodePtr node
 
std::string topicPrefix
 
event::ConnectionPtr updateConnection
 

Detailed Description

Definition at line 31 of file FinROSPlugin.hh.

Constructor & Destructor Documentation

uuv_simulator_ros::FinROSPlugin::FinROSPlugin ( )

Constrcutor.

Definition at line 28 of file FinROSPlugin.cc.

uuv_simulator_ros::FinROSPlugin::~FinROSPlugin ( )

Destructor.

Definition at line 35 of file FinROSPlugin.cc.

Member Function Documentation

bool uuv_simulator_ros::FinROSPlugin::GetLiftDragParams ( uuv_gazebo_ros_plugins_msgs::GetListParam::Request &  _req,
uuv_gazebo_ros_plugins_msgs::GetListParam::Response &  _res 
)

Return the list of paramaters of the lift and drag model.

Definition at line 174 of file FinROSPlugin.cc.

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

Return the ROS publish period.

Definition at line 60 of file FinROSPlugin.cc.

void uuv_simulator_ros::FinROSPlugin::Init ( )
virtual

Initialize Module.

Reimplemented from gazebo::FinPlugin.

Definition at line 75 of file FinROSPlugin.cc.

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

Load module and read parameters from SDF.

Definition at line 87 of file FinROSPlugin.cc.

void uuv_simulator_ros::FinROSPlugin::Reset ( )
virtual

Reset Module.

Definition at line 81 of file FinROSPlugin.cc.

void uuv_simulator_ros::FinROSPlugin::RosPublishStates ( )

Publish state via ROS.

Definition at line 146 of file FinROSPlugin.cc.

void uuv_simulator_ros::FinROSPlugin::SetReference ( const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &  _msg)

Set new set point.

Definition at line 47 of file FinROSPlugin.cc.

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

Set the ROS publish frequency (Hz).

Definition at line 66 of file FinROSPlugin.cc.

Member Data Documentation

gazebo::common::Time uuv_simulator_ros::FinROSPlugin::lastRosPublishTime
private

Last time we published a message via ROS.

Definition at line 88 of file FinROSPlugin.hh.

ros::Publisher uuv_simulator_ros::FinROSPlugin::pubFinForce
private

Publisher for current actual thrust.

Definition at line 76 of file FinROSPlugin.hh.

ros::Publisher uuv_simulator_ros::FinROSPlugin::pubState
private

Publisher for current state.

Definition at line 73 of file FinROSPlugin.hh.

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

Pointer to this ROS node's handle.

Definition at line 67 of file FinROSPlugin.hh.

gazebo::event::ConnectionPtr uuv_simulator_ros::FinROSPlugin::rosPublishConnection
private

Connection for callbacks on update world.

Definition at line 79 of file FinROSPlugin.hh.

gazebo::common::Time uuv_simulator_ros::FinROSPlugin::rosPublishPeriod
private

Period after which we should publish a message via ROS.

Definition at line 82 of file FinROSPlugin.hh.

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

Map of services.

Definition at line 85 of file FinROSPlugin.hh.

ros::Subscriber uuv_simulator_ros::FinROSPlugin::subReference
private

Subscriber reacting to new reference set points.

Definition at line 70 of file FinROSPlugin.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