JointStatePublisher.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 
19 
20 #ifndef __JOINT_STATE_PUBLISHER_HH__
21 #define __JOINT_STATE_PUBLISHER_HH__
22 
23 #include <string>
24 #include <vector>
25 
26 #include <boost/scoped_ptr.hpp>
27 #include <boost/algorithm/string.hpp>
28 #include <gazebo/gazebo.hh>
29 #include <gazebo/common/Plugin.hh>
30 #include <gazebo/common/Event.hh>
31 #include <gazebo/physics/Model.hh>
32 #include <gazebo/physics/Joint.hh>
33 #include <gazebo/physics/World.hh>
34 #include <ros/ros.h>
35 #include <sensor_msgs/JointState.h>
36 #include <sstream>
37 
38 namespace uuv_simulator_ros
39 {
40 class JointStatePublisher : public gazebo::ModelPlugin
41 {
42  public: JointStatePublisher();
43 
44  public: ~JointStatePublisher();
45 
46  public: void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf);
47 
48  public: void OnUpdate(const gazebo::common::UpdateInfo &_info);
49 
50  public: void PublishJointStates();
51 
52  private: bool IsIgnoredJoint(std::string _jointName);
53 
54  private: gazebo::physics::WorldPtr world;
55 
56  private: gazebo::physics::ModelPtr model;
57 
58  private: gazebo::event::ConnectionPtr updateConnection;
59 
61 
62  private: std::string robotNamespace;
63 
64  private: std::vector<std::string> movingJoints;
65 
66  private: double updateRate;
67 
68  private: double updatePeriod;
69 
70  private: gazebo::common::Time lastUpdate;
71 
73 };
74 }
75 
76 #endif // __JOINT_STATE_PUBLISHER_HH__
void OnUpdate(const gazebo::common::UpdateInfo &_info)
bool IsIgnoredJoint(std::string _jointName)
gazebo::event::ConnectionPtr updateConnection
void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf)
boost::shared_ptr< ros::NodeHandle > node


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