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 /*
26  * temporary copied from gazebo_plugins
27  */
28 
29 #ifndef GAZEBO_ROS_PLANAR_MOVE_HH
30 #define GAZEBO_ROS_PLANAR_MOVE_HH
31 
32 #include <boost/bind.hpp>
33 #include <boost/thread.hpp>
34 #include <map>
35 
37 #include <gazebo/common/common.hh>
38 #include <gazebo/physics/physics.hh>
39 #include <sdf/sdf.hh>
40 
42 #include <geometry_msgs/Twist.h>
43 #include <nav_msgs/OccupancyGrid.h>
44 #include <nav_msgs/Odometry.h>
45 #include <ros/advertise_options.h>
46 #include <ros/callback_queue.h>
47 #include <ros/ros.h>
49 #include <tf/transform_listener.h>
50 
51 namespace gazebo {
52 
53  class GazeboRosPlanarForceMove : public ModelPlugin {
54 
55  public:
58  void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
59 
60  protected:
61  virtual void UpdateChild();
62  virtual void FiniChild();
63 
64  private:
65  void publishOdometry(double step_time);
66 
67  physics::ModelPtr parent_;
68  event::ConnectionPtr update_connection_;
69 
74  nav_msgs::Odometry odom_;
75  std::string tf_prefix_;
76 
77  boost::mutex lock;
78 
79  std::string robot_namespace_;
80  std::string command_topic_;
81  std::string odometry_topic_;
82  std::string odometry_frame_;
83  std::string robot_base_frame_;
85 
86  // Custom Callback Queue
88  boost::thread callback_queue_thread_;
89  void QueueThread();
90 
91  // command velocity callback
92  void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg);
93 
94  double x_;
95  double y_;
96  double rot_;
97  bool alive_;
100  ignition::math::Pose3d last_odom_pose_;
101 
103  physics::LinkPtr robot_link_;
105  double v_dead_zone_;
108  };
109 
110 }
111 
112 #endif /* end of include guard: GAZEBO_ROS_PLANAR_MOVE_HH */
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
boost::shared_ptr< ros::NodeHandle > rosnode_
Gazebo.
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
bool enable_y_axis_
Enable Y-axis movement.


seed_r7_gazebo
Author(s):
autogenerated on Sun Apr 18 2021 02:41:01