00001 /* 00002 * Copyright 2013 Open Source Robotics Foundation 00003 * 00004 * Licensed under the Apache License, Version 2.0 (the "License"); 00005 * you may not use this file except in compliance with the License. 00006 * You may obtain a copy of the License at 00007 * 00008 * http://www.apache.org/licenses/LICENSE-2.0 00009 * 00010 * Unless required by applicable law or agreed to in writing, software 00011 * distributed under the License is distributed on an "AS IS" BASIS, 00012 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 00013 * See the License for the specific language governing permissions and 00014 * limitations under the License. 00015 * 00016 */ 00017 00018 /* 00019 * Desc: Simple model controller that uses a twist message to move a robot on 00020 * the xy plane. 00021 * Author: Piyush Khandelwal 00022 * Date: 29 July 2013 00023 */ 00024 00025 #ifndef GAZEBO_ROS_PLANAR_MOVE_HH 00026 #define GAZEBO_ROS_PLANAR_MOVE_HH 00027 00028 #include <boost/bind.hpp> 00029 #include <boost/thread.hpp> 00030 #include <map> 00031 00032 #include <gazebo/common/common.hh> 00033 #include <gazebo/physics/physics.hh> 00034 #include <sdf/sdf.hh> 00035 00036 #include <geometry_msgs/Twist.h> 00037 #include <nav_msgs/OccupancyGrid.h> 00038 #include <nav_msgs/Odometry.h> 00039 #include <ros/advertise_options.h> 00040 #include <ros/callback_queue.h> 00041 #include <ros/ros.h> 00042 #include <tf/transform_broadcaster.h> 00043 #include <tf/transform_listener.h> 00044 00045 namespace gazebo { 00046 00047 class GazeboRosPlanarMove : public ModelPlugin { 00048 00049 public: 00050 GazeboRosPlanarMove(); 00051 ~GazeboRosPlanarMove(); 00052 void Load(physics::ModelPtr parent, sdf::ElementPtr sdf); 00053 00054 protected: 00055 virtual void UpdateChild(); 00056 virtual void FiniChild(); 00057 00058 private: 00059 void publishOdometry(double step_time); 00060 00061 physics::ModelPtr parent_; 00062 event::ConnectionPtr update_connection_; 00063 00064 boost::shared_ptr<ros::NodeHandle> rosnode_; 00065 ros::Publisher odometry_pub_; 00066 ros::Subscriber vel_sub_; 00067 boost::shared_ptr<tf::TransformBroadcaster> transform_broadcaster_; 00068 nav_msgs::Odometry odom_; 00069 std::string tf_prefix_; 00070 00071 boost::mutex lock; 00072 00073 std::string robot_namespace_; 00074 std::string command_topic_; 00075 std::string odometry_topic_; 00076 std::string odometry_frame_; 00077 std::string robot_base_frame_; 00078 double odometry_rate_; 00079 00080 // Custom Callback Queue 00081 ros::CallbackQueue queue_; 00082 boost::thread callback_queue_thread_; 00083 void QueueThread(); 00084 00085 // command velocity callback 00086 void cmdVelCallback(const geometry_msgs::Twist::ConstPtr& cmd_msg); 00087 00088 double x_; 00089 double y_; 00090 double rot_; 00091 bool alive_; 00092 common::Time last_odom_publish_time_; 00093 math::Pose last_odom_pose_; 00094 00095 }; 00096 00097 } 00098 00099 #endif /* end of include guard: GAZEBO_ROS_PLANAR_MOVE_HH */