80 #if (GAZEBO_MAJOR_VERSION < 8) 81 #include <gazebo/math/gzmath.hh> 88 #include <geometry_msgs/Twist.h> 89 #include <nav_msgs/GetMap.h> 90 #include <nav_msgs/Odometry.h> 91 #include <boost/bind.hpp> 92 #include <boost/thread/mutex.hpp> 93 #include <boost/algorithm/string/split.hpp> 94 #include <boost/algorithm/string/classification.hpp> 96 #include <gazebo/gazebo_config.h> 117 this->
world = _parent->GetWorld();
120 if (!_sdf->HasElement(
"robotNamespace")) {
121 ROS_INFO(
"GazeboRosDiffDriveMultiWheel Plugin missing <robotNamespace>, defaults to \"%s\"",
125 _sdf->GetElement(
"robotNamespace")->Get<std::string>() +
"/";
129 if (!_sdf->HasElement(
"leftJoints")) {
130 gzthrow(
"Have to specify space separated left side joint names via <leftJoints> tag!");
132 std::string joint_string = _sdf->GetElement(
"leftJoints")->Get<std::string>();
137 if (!_sdf->HasElement(
"rightJoints")) {
138 gzthrow(
"Have to specify space separated right side joint names via <rightJoints> tag!");
140 std::string joint_string = _sdf->GetElement(
"rightJoints")->Get<std::string>();
145 if (!_sdf->HasElement(
"wheelSeparation")) {
146 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <wheelSeparation>, defaults to %f",
150 _sdf->GetElement(
"wheelSeparation")->Get<
double>();
154 if (!_sdf->HasElement(
"wheelDiameter")) {
155 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <wheelDiameter>, defaults to %f",
158 this->wheel_diameter_ = _sdf->GetElement(
"wheelDiameter")->Get<
double>();
162 if (!_sdf->HasElement(
"torque")) {
163 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <torque>, defaults to %f",
166 this->torque = _sdf->GetElement(
"torque")->Get<
double>();
170 if (!_sdf->HasElement(
"commandTopic")) {
171 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <commandTopic>, defaults to \"%s\"",
174 this->command_topic_ = _sdf->GetElement(
"commandTopic")->Get<std::string>();
178 if (!_sdf->HasElement(
"odometryTopic")) {
179 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <odometryTopic>, defaults to \"%s\"",
182 this->odometry_topic_ = _sdf->GetElement(
"odometryTopic")->Get<std::string>();
186 if (!_sdf->HasElement(
"odometryFrame")) {
187 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <odometryFrame>, defaults to \"%s\"",
190 this->odometry_frame_ = _sdf->GetElement(
"odometryFrame")->Get<std::string>();
194 if (!_sdf->HasElement(
"robotBaseFrame")) {
195 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <robotBaseFrame>, defaults to \"%s\"",
198 this->robot_base_frame_ = _sdf->GetElement(
"robotBaseFrame")->Get<std::string>();
202 if (!_sdf->HasElement(
"updateRate")) {
203 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <updateRate>, defaults to %f",
206 this->update_rate_ = _sdf->GetElement(
"updateRate")->Get<
double>();
211 if (!_sdf->HasElement(
"publishOdometryTf")) {
212 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <publishOdometryTf>, defaults to %s",
213 this->
robot_namespace_.c_str(), this->publish_odometry_tf_ ?
"true" :
"false");
215 this->publish_odometry_tf_ = _sdf->GetElement(
"publishOdometryTf")->Get<
bool>();
219 if (!_sdf->HasElement(
"publishOdometryMsg")) {
220 ROS_WARN(
"GazeboRosDiffDriveMultiWheel Plugin (ns = %s) missing <publishOdometryMsg>, defaults to %s",
221 this->
robot_namespace_.c_str(), this->publish_odometry_msg_ ?
"true" :
"false");
223 this->publish_odometry_msg_ = _sdf->GetElement(
"publishOdometryMsg")->Get<
bool>();
229 if (this->update_rate_ > 0.0) {
234 #if (GAZEBO_MAJOR_VERSION >= 8) 248 for (
size_t side = 0; side < 2; ++side){
254 "GazeboRosDiffDriveMultiWheel Plugin (ns = %s) couldn't get hinge joint named \"%s\"",
258 #if (GAZEBO_MAJOR_VERSION > 4) 259 joints_[side][i]->SetEffortLimit(0, torque);
261 joints_[side][i]->SetMaxForce(0, torque);
269 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 270 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
283 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
297 event::Events::ConnectWorldUpdateBegin(
304 #if (GAZEBO_MAJOR_VERSION >= 8) 305 common::Time current_time = this->
world->SimTime();
307 common::Time current_time = this->
world->GetSimTime();
309 double seconds_since_last_update =
322 for (
size_t side = 0; side < 2; ++side){
323 for (
size_t i = 0; i <
joints_[side].size(); ++i){
343 boost::mutex::scoped_lock scoped_lock(
lock);
353 const geometry_msgs::Twist::ConstPtr& cmd_msg) {
355 boost::mutex::scoped_lock scoped_lock(
lock);
356 x_ = cmd_msg->linear.x;
357 rot_ = cmd_msg->angular.z;
361 static const double timeout = 0.01;
370 std::string odom_frame =
372 std::string base_footprint_frame =
376 #if (GAZEBO_MAJOR_VERSION >= 8) 377 ignition::math::Pose3d pose = this->
parent->WorldPose();
379 tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W());
380 tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z());
382 math::Pose pose = this->
parent->GetWorldPose();
384 tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
385 tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
393 odom_frame, base_footprint_frame));
397 #if (GAZEBO_MAJOR_VERSION >= 8) 398 odom_.pose.pose.position.x = pose.Pos().X();
399 odom_.pose.pose.position.y = pose.Pos().Y();
401 odom_.pose.pose.orientation.x = pose.Rot().X();
402 odom_.pose.pose.orientation.y = pose.Rot().Y();
403 odom_.pose.pose.orientation.z = pose.Rot().Z();
404 odom_.pose.pose.orientation.w = pose.Rot().W();
406 odom_.pose.pose.position.x = pose.pos.x;
407 odom_.pose.pose.position.y = pose.pos.y;
409 odom_.pose.pose.orientation.x = pose.rot.x;
410 odom_.pose.pose.orientation.y = pose.rot.y;
411 odom_.pose.pose.orientation.z = pose.rot.z;
412 odom_.pose.pose.orientation.w = pose.rot.w;
414 odom_.pose.covariance[0] = 0.00001;
415 odom_.pose.covariance[7] = 0.00001;
416 odom_.pose.covariance[14] = 1000000000000.0;
417 odom_.pose.covariance[21] = 1000000000000.0;
418 odom_.pose.covariance[28] = 1000000000000.0;
419 odom_.pose.covariance[35] = 0.001;
422 #if (GAZEBO_MAJOR_VERSION >= 8) 423 ignition::math::Vector3d linear;
424 linear = this->
parent->WorldLinearVel();
425 odom_.twist.twist.angular.z = this->
parent->WorldAngularVel().Z();
427 math::Vector3 linear;
428 linear = this->
parent->GetWorldLinearVel();
429 odom_.twist.twist.angular.z = this->
parent->GetWorldAngularVel().z;
433 #if (GAZEBO_MAJOR_VERSION >= 8) 434 float yaw = pose.Rot().Yaw();
435 odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y();
436 odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X();
438 float yaw = pose.rot.GetYaw();
439 odom_.twist.twist.linear.x = cosf(yaw) * linear.x + sinf(yaw) * linear.y;
440 odom_.twist.twist.linear.y = cosf(yaw) * linear.y - sinf(yaw) * linear.x;
443 odom_.header.stamp = current_time;
444 odom_.header.frame_id = odom_frame;
445 odom_.child_frame_id = base_footprint_frame;
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
std::string odometry_topic_
ros::NodeHandle * rosnode_
std::vector< std::string > joint_names_[2]
std::string robot_namespace_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL bool isInitialized()
GazeboRosDiffDriveMultiWheel()
virtual void UpdateChild()
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
ros::CallbackQueue queue_
std::string command_topic_
ros::Subscriber cmd_vel_subscriber_
std::string resolve(const std::string &prefix, const std::string &frame_name)
tf::TransformBroadcaster * transform_broadcaster_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
std::vector< physics::JointPtr > joints_[2]
#define ROS_FATAL_STREAM(args)
std::string robot_base_frame_
~GazeboRosDiffDriveMultiWheel()
event::ConnectionPtr update_connection_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::thread callback_queue_thread_
common::Time last_update_time_
void getWheelVelocities()
bool publish_odometry_msg_
ros::Publisher odometry_publisher_
std::string odometry_frame_
boost::shared_ptr< void > VoidPtr
void publishOdometry(double step_time)
bool publish_odometry_tf_