16 #ifndef __FIN_ROS_PLUGIN_HH__ 17 #define __FIN_ROS_PLUGIN_HH__ 21 #include <boost/scoped_ptr.hpp> 22 #include <gazebo/common/Plugin.hh> 24 #include <uuv_gazebo_ros_plugins_msgs/FloatStamped.h> 25 #include <uuv_gazebo_ros_plugins_msgs/GetListParam.h> 26 #include <geometry_msgs/WrenchStamped.h> 40 public:
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf);
47 const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg);
51 uuv_gazebo_ros_plugins_msgs::GetListParam::Request& _req,
52 uuv_gazebo_ros_plugins_msgs::GetListParam::Response& _res);
61 public:
virtual void Init();
64 public:
virtual void Reset();
67 private: boost::scoped_ptr<ros::NodeHandle>
rosNode;
85 private: std::map<std::string, ros::ServiceServer>
services;
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
std::map< std::string, ros::ServiceServer > services
Map of services.
ros::Publisher pubFinForce
Publisher for current actual thrust.
virtual void Reset()
Reset Module.
~FinROSPlugin()
Destructor.
FinROSPlugin()
Constrcutor.
gazebo::event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
void RosPublishStates()
Publish state via ROS.
void SetRosPublishRate(double _hz)
Set the ROS publish frequency (Hz).
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.
gazebo::common::Time rosPublishPeriod
Period after which we should publish a message via ROS.
void SetReference(const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg)
Set new set point.
virtual void Init()
Initialize Module.
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node's handle.
gazebo::common::Time lastRosPublishTime
Last time we published a message via ROS.
ros::Publisher pubState
Publisher for current state.
ros::Subscriber subReference
Subscriber reacting to new reference set points.
gazebo::common::Time GetRosPublishPeriod()
Return the ROS publish period.