FinROSPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
16 #ifndef __FIN_ROS_PLUGIN_HH__
17 #define __FIN_ROS_PLUGIN_HH__
18 
20 
21 #include <boost/scoped_ptr.hpp>
22 #include <gazebo/common/Plugin.hh>
23 #include <ros/ros.h>
24 #include <uuv_gazebo_ros_plugins_msgs/FloatStamped.h>
25 #include <uuv_gazebo_ros_plugins_msgs/GetListParam.h>
26 #include <geometry_msgs/WrenchStamped.h>
27 #include <map>
28 
30 {
32  {
34  public: FinROSPlugin();
35 
37  public: ~FinROSPlugin();
38 
40  public: void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf);
41 
43  public: void RosPublishStates();
44 
46  public: void SetReference(
47  const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg);
48 
50  public: bool GetLiftDragParams(
51  uuv_gazebo_ros_plugins_msgs::GetListParam::Request& _req,
52  uuv_gazebo_ros_plugins_msgs::GetListParam::Response& _res);
53 
55  public: gazebo::common::Time GetRosPublishPeriod();
56 
58  public: void SetRosPublishRate(double _hz);
59 
61  public: virtual void Init();
62 
64  public: virtual void Reset();
65 
67  private: boost::scoped_ptr<ros::NodeHandle> rosNode;
68 
71 
74 
77 
79  private: gazebo::event::ConnectionPtr rosPublishConnection;
80 
82  private: gazebo::common::Time rosPublishPeriod;
83 
85  private: std::map<std::string, ros::ServiceServer> services;
86 
88  private: gazebo::common::Time lastRosPublishTime;
89  };
90 }
91 
92 #endif
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
Load module and read parameters from SDF.
Definition: FinROSPlugin.cc:87
std::map< std::string, ros::ServiceServer > services
Map of services.
Definition: FinROSPlugin.hh:85
ros::Publisher pubFinForce
Publisher for current actual thrust.
Definition: FinROSPlugin.hh:76
virtual void Reset()
Reset Module.
Definition: FinROSPlugin.cc:81
gazebo::event::ConnectionPtr rosPublishConnection
Connection for callbacks on update world.
Definition: FinROSPlugin.hh:79
void RosPublishStates()
Publish state via ROS.
void SetRosPublishRate(double _hz)
Set the ROS publish frequency (Hz).
Definition: FinROSPlugin.cc:66
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.
Definition: FinROSPlugin.hh:82
void SetReference(const uuv_gazebo_ros_plugins_msgs::FloatStamped::ConstPtr &_msg)
Set new set point.
Definition: FinROSPlugin.cc:47
virtual void Init()
Initialize Module.
Definition: FinROSPlugin.cc:75
boost::scoped_ptr< ros::NodeHandle > rosNode
Pointer to this ROS node&#39;s handle.
Definition: FinROSPlugin.hh:67
gazebo::common::Time lastRosPublishTime
Last time we published a message via ROS.
Definition: FinROSPlugin.hh:88
ros::Publisher pubState
Publisher for current state.
Definition: FinROSPlugin.hh:73
ros::Subscriber subReference
Subscriber reacting to new reference set points.
Definition: FinROSPlugin.hh:70
gazebo::common::Time GetRosPublishPeriod()
Return the ROS publish period.
Definition: FinROSPlugin.cc:60


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