#include <FinROSPlugin.hh>

| 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::NodeHandle > | rosNode | 
| 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::ServiceServer > | services | 
| 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< Dynamics > | dynamics | 
| ignition::math::Vector3d | finForce | 
| int | finID | 
| double | inputCommand | 
| physics::JointPtr | joint | 
| std::shared_ptr< LiftDrag > | liftdrag | 
| physics::LinkPtr | link | 
| transport::NodePtr | node | 
| std::string | topicPrefix | 
| event::ConnectionPtr | updateConnection | 
Definition at line 31 of file FinROSPlugin.hh.
| 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.
| 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.
| 
 | 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.
| 
 | 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.
| 
 | private | 
Last time we published a message via ROS.
Definition at line 88 of file FinROSPlugin.hh.
| 
 | private | 
Publisher for current actual thrust.
Definition at line 76 of file FinROSPlugin.hh.
| 
 | private | 
Publisher for current state.
Definition at line 73 of file FinROSPlugin.hh.
| 
 | private | 
Pointer to this ROS node's handle.
Definition at line 67 of file FinROSPlugin.hh.
| 
 | private | 
Connection for callbacks on update world.
Definition at line 79 of file FinROSPlugin.hh.
| 
 | private | 
Period after which we should publish a message via ROS.
Definition at line 82 of file FinROSPlugin.hh.
| 
 | private | 
Map of services.
Definition at line 85 of file FinROSPlugin.hh.
| 
 | private | 
Subscriber reacting to new reference set points.
Definition at line 70 of file FinROSPlugin.hh.