gazebo_ros_planar_move.h
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Open Source Robotics Foundation
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 */
17 
18 /*
19  * Desc: Simple model controller that uses a twist message to move a robot on
20  * the xy plane.
21  * Author: Piyush Khandelwal
22  * Date: 29 July 2013
23  */
24 
25 #ifndef GAZEBO_ROS_PLANAR_MOVE_HH
26 #define GAZEBO_ROS_PLANAR_MOVE_HH
27 
28 #include <boost/bind.hpp>
29 #include <boost/thread.hpp>
30 #include <map>
31 
32 #include <gazebo/common/common.hh>
33 #include <gazebo/physics/physics.hh>
34 #include <sdf/sdf.hh>
35 
36 #include <geometry_msgs/Twist.h>
37 #include <nav_msgs/OccupancyGrid.h>
38 #include <nav_msgs/Odometry.h>
39 #include <ros/advertise_options.h>
40 #include <ros/callback_queue.h>
41 #include <ros/ros.h>
43 #include <tf/transform_listener.h>
44 
45 namespace gazebo {
46 
47  class GazeboRosPlanarMove : public ModelPlugin {
48 
49  public:
52  void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
53 
54  protected:
55  virtual void UpdateChild();
56  virtual void FiniChild();
57 
58  private:
59  void publishOdometry(double step_time);
60 
61  physics::ModelPtr parent_;
62  event::ConnectionPtr update_connection_;
63 
68  nav_msgs::Odometry odom_;
69  std::string tf_prefix_;
70 
71  boost::mutex lock;
72 
73  std::string robot_namespace_;
74  std::string command_topic_;
75  std::string odometry_topic_;
76  std::string odometry_frame_;
77  std::string robot_base_frame_;
79 
80  // Custom Callback Queue
82  boost::thread callback_queue_thread_;
83  void QueueThread();
84 
85  // command velocity callback
86  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
87 
88  double x_;
89  double y_;
90  double rot_;
91  bool alive_;
93  ignition::math::Pose3d last_odom_pose_;
94 
95  };
96 
97 }
98 
99 #endif /* end of include guard: GAZEBO_ROS_PLANAR_MOVE_HH */
boost::shared_ptr< ros::NodeHandle > rosnode_
ignition::math::Pose3d last_odom_pose_
void publishOdometry(double step_time)
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
event::ConnectionPtr update_connection_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27