20 #ifndef __UNDERWATER_CURRENT_ROS_PLUGIN_HH__ 21 #define __UNDERWATER_CURRENT_ROS_PLUGIN_HH__ 29 #include <boost/scoped_ptr.hpp> 30 #include <gazebo/common/Plugin.hh> 31 #include <gazebo/physics/World.hh> 33 #include <geometry_msgs/TwistStamped.h> 34 #include <uuv_world_ros_plugins_msgs/SetCurrentModel.h> 35 #include <uuv_world_ros_plugins_msgs/GetCurrentModel.h> 36 #include <uuv_world_ros_plugins_msgs/SetCurrentVelocity.h> 37 #include <uuv_world_ros_plugins_msgs/SetCurrentDirection.h> 38 #include <uuv_world_ros_plugins_msgs/SetOriginSphericalCoord.h> 39 #include <uuv_world_ros_plugins_msgs/GetOriginSphericalCoord.h> 52 public:
void Load(gazebo::physics::WorldPtr _world,
53 sdf::ElementPtr _sdf);
58 uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
59 uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
64 uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
65 uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
70 uuv_world_ros_plugins_msgs::SetCurrentModel::Request& _req,
71 uuv_world_ros_plugins_msgs::SetCurrentModel::Response& _res);
76 uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
77 uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
82 uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
83 uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
88 uuv_world_ros_plugins_msgs::GetCurrentModel::Request& _req,
89 uuv_world_ros_plugins_msgs::GetCurrentModel::Response& _res);
93 uuv_world_ros_plugins_msgs::SetCurrentVelocity::Request& _req,
94 uuv_world_ros_plugins_msgs::SetCurrentVelocity::Response& _res);
98 uuv_world_ros_plugins_msgs::SetCurrentDirection::Request& _req,
99 uuv_world_ros_plugins_msgs::SetCurrentDirection::Response& _res);
103 uuv_world_ros_plugins_msgs::SetCurrentDirection::Request& _req,
104 uuv_world_ros_plugins_msgs::SetCurrentDirection::Response& _res);
113 private: boost::scoped_ptr<ros::NodeHandle>
rosNode;
129 #endif // __UNDERWATER_CURRENT_ROS_PLUGIN_HH__ ros::Publisher flowVelocityPub
Publisher for the flow velocity in the world frame.
gazebo::common::Time rosPublishPeriod
Period after which we should publish a message via ROS.
bool UpdateCurrentVertAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentModel::Response &_res)
Service call to update the parameters for the vertical angle Gauss-Markov process model...
bool UpdateCurrentVelocity(uuv_world_ros_plugins_msgs::SetCurrentVelocity::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentVelocity::Response &_res)
Service call to update the mean value of the flow velocity.
bool GetCurrentVelocityModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::GetCurrentModel::Response &_res)
Service call to read the parameters for the velocity Gauss-Markov process model.
virtual ~UnderwaterCurrentROSPlugin()
Class destructor.
void OnUpdateCurrentVel()
Publishes ROS topics.
bool UpdateHorzAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentDirection::Response &_res)
Service call to update the mean value of the horizontal angle.
bool UpdateCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentModel::Response &_res)
Service call to update the parameters for the horizontal angle Gauss-Markov process model...
gazebo::common::Time lastRosPublishTime
Last time we published a message via ROS.
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node's handle.
bool UpdateVertAngle(uuv_world_ros_plugins_msgs::SetCurrentDirection::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentDirection::Response &_res)
Service call to update the mean value of the vertical angle.
bool UpdateCurrentVelocityModel(uuv_world_ros_plugins_msgs::SetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::SetCurrentModel::Response &_res)
Service call to update the parameters for the velocity Gauss-Markov process model.
UnderwaterCurrentROSPlugin()
Class constructor.
bool GetCurrentHorzAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::GetCurrentModel::Response &_res)
Service call to read the parameters for the horizontal angle Gauss-Markov process model...
std::map< std::string, ros::ServiceServer > worldServices
All underwater world services.
void Load(gazebo::physics::WorldPtr _world, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
gazebo::event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
bool GetCurrentVertAngleModel(uuv_world_ros_plugins_msgs::GetCurrentModel::Request &_req, uuv_world_ros_plugins_msgs::GetCurrentModel::Response &_res)
Service call to read the parameters for the vertical angle Gauss-Markov process model.