55 #include <ignition/math/Angle.hh> 56 #include <ignition/math/Pose3.hh> 57 #include <ignition/math/Quaternion.hh> 58 #include <ignition/math/Vector3.hh> 93 if (!_sdf->HasElement(
"legacyMode"))
95 ROS_ERROR_NAMED(
"diff_drive",
"GazeboRosDiffDrive Plugin missing <legacyMode>, defaults to true\n" 96 "This setting assumes you have a old package, where the right and left wheel are changed to fix a former code issue\n" 97 "To get rid of this error just set <legacyMode> to false if you just created a new package.\n" 98 "To fix an old package you have to exchange left wheel by the right wheel.\n" 99 "If you do not want to fix this issue in an old package or your z axis points down instead of the ROS standard defined in REP 103\n" 100 "just set <legacyMode> to true.\n" 109 std::map<std::string, OdomSource> odomOptions;
110 odomOptions[
"encoder"] =
ENCODER;
111 odomOptions[
"world"] =
WORLD;
118 joints_[
LEFT]->SetParam (
"fmax", 0, wheel_torque );
124 if (!_sdf->HasElement(
"publishTf")) {
125 ROS_WARN_NAMED(
"diff_drive",
"GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
128 this->
publish_tf_ = _sdf->GetElement(
"publishTf")->Get<
bool>();
134 #if GAZEBO_MAJOR_VERSION >= 8 165 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
190 #if GAZEBO_MAJOR_VERSION >= 8 212 for (
int i = 0; i < 2; i++ ) {
213 physics::JointPtr joint =
joints_[i];
214 #if GAZEBO_MAJOR_VERSION >= 8 215 double position = joint->Position ( 0 );
217 double position = joint->GetAngle ( 0 ).Radian();
228 for (
int i = 0; i < 2; i++ ) {
231 std::string wheel_parent_frame =
gazebo_ros_->resolveTF(
joints_[i]->GetParent()->GetName ());
233 #if GAZEBO_MAJOR_VERSION >= 8 234 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->RelativePose();
236 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->GetRelativePose().Ign();
239 tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() );
240 tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() );
258 for (
int i = 0; i < 2; i++ ) {
266 #if GAZEBO_MAJOR_VERSION >= 8 267 common::Time current_time =
parent->GetWorld()->SimTime();
269 common::Time current_time =
parent->GetWorld()->GetSimTime();
271 double seconds_since_last_update = ( current_time -
last_update_time_ ).Double();
281 double current_speed[2];
325 boost::mutex::scoped_lock scoped_lock (
lock );
344 boost::mutex::scoped_lock scoped_lock (
lock );
345 x_ = cmd_msg->linear.x;
346 rot_ = cmd_msg->angular.z;
351 static const double timeout = 0.01;
362 #if GAZEBO_MAJOR_VERSION >= 8 363 common::Time current_time =
parent->GetWorld()->SimTime();
365 common::Time current_time =
parent->GetWorld()->GetSimTime();
367 double seconds_since_last_update = ( current_time -
last_odom_update_ ).Double();
373 double sl = vl * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
374 double sr = vr * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
375 double ssum = sl + sr;
388 double dx = ( ssum ) /2.0 * cos (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
389 double dy = ( ssum ) /2.0 * sin (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
390 double dtheta = ( sdiff ) /b;
396 double w = dtheta/seconds_since_last_update;
397 double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
404 odom_.pose.pose.position.x = vt.
x();
405 odom_.pose.pose.position.y = vt.
y();
406 odom_.pose.pose.position.z = vt.
z();
408 odom_.pose.pose.orientation.x = qt.x();
409 odom_.pose.pose.orientation.y = qt.y();
410 odom_.pose.pose.orientation.z = qt.z();
411 odom_.pose.pose.orientation.w = qt.w();
413 odom_.twist.twist.angular.z = w;
414 odom_.twist.twist.linear.x = dx/seconds_since_last_update;
415 odom_.twist.twist.linear.y = dy/seconds_since_last_update;
436 #if GAZEBO_MAJOR_VERSION >= 8 437 ignition::math::Pose3d pose =
parent->WorldPose();
439 ignition::math::Pose3d pose =
parent->GetWorldPose().Ign();
441 qt =
tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
442 vt =
tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
444 odom_.pose.pose.position.x = vt.x();
445 odom_.pose.pose.position.y = vt.y();
446 odom_.pose.pose.position.z = vt.z();
448 odom_.pose.pose.orientation.x = qt.x();
449 odom_.pose.pose.orientation.y = qt.y();
450 odom_.pose.pose.orientation.z = qt.z();
451 odom_.pose.pose.orientation.w = qt.w();
454 ignition::math::Vector3d linear;
455 #if GAZEBO_MAJOR_VERSION >= 8 456 linear =
parent->WorldLinearVel();
457 odom_.twist.twist.angular.z =
parent->WorldAngularVel().Z();
459 linear =
parent->GetWorldLinearVel().Ign();
460 odom_.twist.twist.angular.z =
parent->GetWorldAngularVel().Ign().Z();
464 float yaw = pose.Rot().Yaw();
465 odom_.twist.twist.linear.x = cosf ( yaw ) * linear.X() + sinf ( yaw ) * linear.Y();
466 odom_.twist.twist.linear.y = cosf ( yaw ) * linear.Y() - sinf ( yaw ) * linear.X();
472 odom_frame, base_footprint_frame ) );
476 odom_.pose.covariance[0] = 0.00001;
477 odom_.pose.covariance[7] = 0.00001;
478 odom_.pose.covariance[14] = 1000000000000.0;
479 odom_.pose.covariance[21] = 1000000000000.0;
480 odom_.pose.covariance[28] = 1000000000000.0;
481 odom_.pose.covariance[35] = 0.001;
485 odom_.header.stamp = current_time;
486 odom_.header.frame_id = odom_frame;
487 odom_.child_frame_id = base_footprint_frame;
#define ROS_INFO_NAMED(name,...)
void publish(const boost::shared_ptr< M > &message) const
#define ROS_WARN_NAMED(name,...)
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
boost::thread callback_queue_thread_
void UpdateOdometryEncoder()
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
std::string odometry_frame_
std::string robot_namespace_
ros::Publisher joint_state_publisher_
TFSIMD_FORCE_INLINE const tfScalar & x() const
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
bool publishWheelJointState_
ros::Publisher odometry_publisher_
common::Time last_update_time_
event::ConnectionPtr update_connection_
TFSIMD_FORCE_INLINE const tfScalar & z() const
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void getWheelVelocities()
sensor_msgs::JointState joint_state_
ros::Subscriber cmd_vel_subscriber_
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::CallbackQueue queue_
TFSIMD_FORCE_INLINE const tfScalar & w() const
std::string odometry_topic_
double wheel_speed_instr_[2]
std::string command_topic_
std::string robot_base_frame_
virtual void UpdateChild()
void publishOdometry(double step_time)
#define ROS_ERROR_NAMED(name,...)
void publishWheelJointState()
publishes the wheel tf's
geometry_msgs::Pose2D pose_encoder_
void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf)
boost::shared_ptr< void > VoidPtr
boost::shared_ptr< GazeboRos > GazeboRosPtr
common::Time last_odom_update_
std::vector< physics::JointPtr > joints_