55 #include <ignition/math/Angle.hh> 56 #include <ignition/math/Pose3.hh> 57 #include <ignition/math/Quaternion.hh> 58 #include <ignition/math/Vector3.hh> 100 std::map<std::string, OdomSource> odomOptions;
101 odomOptions[
"encoder"] =
ENCODER;
102 odomOptions[
"world"] =
WORLD;
109 joints_[
LEFT]->SetParam (
"fmax", 0, wheel_torque );
115 if (!_sdf->HasElement(
"publishTf")) {
116 ROS_WARN_NAMED(
"diff_drive",
"GazeboRosDiffDrive Plugin (ns = %s) missing <publishTf>, defaults to %d",
119 this->
publish_tf_ = _sdf->GetElement(
"publishTf")->Get<
bool>();
125 #if GAZEBO_MAJOR_VERSION >= 8 156 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
181 #if GAZEBO_MAJOR_VERSION >= 8 203 for (
int i = 0; i < 2; i++ ) {
204 physics::JointPtr joint =
joints_[i];
205 #if GAZEBO_MAJOR_VERSION >= 8 206 double position = joint->Position ( 0 );
208 double position = joint->GetAngle ( 0 ).Radian();
219 for (
int i = 0; i < 2; i++ ) {
222 std::string wheel_parent_frame =
gazebo_ros_->resolveTF(
joints_[i]->GetParent()->GetName ());
224 #if GAZEBO_MAJOR_VERSION >= 8 225 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->RelativePose();
227 ignition::math::Pose3d poseWheel =
joints_[i]->GetChild()->GetRelativePose().Ign();
230 tf::Quaternion qt ( poseWheel.Rot().X(), poseWheel.Rot().Y(), poseWheel.Rot().Z(), poseWheel.Rot().W() );
231 tf::Vector3 vt ( poseWheel.Pos().X(), poseWheel.Pos().Y(), poseWheel.Pos().Z() );
249 for (
int i = 0; i < 2; i++ ) {
257 #if GAZEBO_MAJOR_VERSION >= 8 258 common::Time current_time =
parent->GetWorld()->SimTime();
260 common::Time current_time =
parent->GetWorld()->GetSimTime();
262 double seconds_since_last_update = ( current_time -
last_update_time_ ).Double();
272 double current_speed[2];
316 boost::mutex::scoped_lock scoped_lock (
lock );
327 boost::mutex::scoped_lock scoped_lock (
lock );
328 x_ = cmd_msg->linear.x;
329 rot_ = cmd_msg->angular.z;
334 static const double timeout = 0.01;
345 #if GAZEBO_MAJOR_VERSION >= 8 346 common::Time current_time =
parent->GetWorld()->SimTime();
348 common::Time current_time =
parent->GetWorld()->GetSimTime();
350 double seconds_since_last_update = ( current_time -
last_odom_update_ ).Double();
356 double sl = vl * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
357 double sr = vr * (
wheel_diameter_ / 2.0 ) * seconds_since_last_update;
358 double ssum = sl + sr;
360 double sdiff = sr - sl;
362 double dx = ( ssum ) /2.0 * cos (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
363 double dy = ( ssum ) /2.0 * sin (
pose_encoder_.theta + ( sdiff ) / ( 2.0*b ) );
364 double dtheta = ( sdiff ) /b;
370 double w = dtheta/seconds_since_last_update;
371 double v = sqrt ( dx*dx+dy*dy ) /seconds_since_last_update;
378 odom_.pose.pose.position.x = vt.x();
379 odom_.pose.pose.position.y = vt.y();
380 odom_.pose.pose.position.z = vt.z();
382 odom_.pose.pose.orientation.x = qt.x();
383 odom_.pose.pose.orientation.y = qt.y();
384 odom_.pose.pose.orientation.z = qt.z();
385 odom_.pose.pose.orientation.w = qt.w();
387 odom_.twist.twist.angular.z = w;
388 odom_.twist.twist.linear.x = v;
389 odom_.twist.twist.linear.y = 0;
405 vt = tf::Vector3 (
odom_.pose.pose.position.x,
odom_.pose.pose.position.y,
odom_.pose.pose.position.z );
410 #if GAZEBO_MAJOR_VERSION >= 8 411 ignition::math::Pose3d pose =
parent->WorldPose();
413 ignition::math::Pose3d pose =
parent->GetWorldPose().Ign();
415 qt =
tf::Quaternion ( pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W() );
416 vt = tf::Vector3 ( pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z() );
418 odom_.pose.pose.position.x = vt.x();
419 odom_.pose.pose.position.y = vt.y();
420 odom_.pose.pose.position.z = vt.z();
422 odom_.pose.pose.orientation.x = qt.x();
423 odom_.pose.pose.orientation.y = qt.y();
424 odom_.pose.pose.orientation.z = qt.z();
425 odom_.pose.pose.orientation.w = qt.w();
428 ignition::math::Vector3d linear;
429 #if GAZEBO_MAJOR_VERSION >= 8 430 linear =
parent->WorldLinearVel();
431 odom_.twist.twist.angular.z =
parent->WorldAngularVel().Z();
433 linear =
parent->GetWorldLinearVel().Ign();
434 odom_.twist.twist.angular.z =
parent->GetWorldAngularVel().Ign().Z();
438 float yaw = pose.Rot().Yaw();
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();
447 odom_frame, base_footprint_frame ) );
452 odom_.pose.covariance[0] = 0.00001;
453 odom_.pose.covariance[7] = 0.00001;
454 odom_.pose.covariance[14] = 1000000000000.0;
455 odom_.pose.covariance[21] = 1000000000000.0;
456 odom_.pose.covariance[28] = 1000000000000.0;
457 odom_.pose.covariance[35] = 0.001;
461 odom_.header.stamp = current_time;
462 odom_.header.frame_id = odom_frame;
463 odom_.child_frame_id = base_footprint_frame;
#define ROS_INFO_NAMED(name,...)
#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_
GZ_REGISTER_MODEL_PLUGIN(GazeboRosF3D)
bool publishWheelJointState_
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher odometry_publisher_
common::Time last_update_time_
event::ConnectionPtr update_connection_
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
void getWheelVelocities()
sensor_msgs::JointState joint_state_
ros::Subscriber cmd_vel_subscriber_
ros::CallbackQueue queue_
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)
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_