26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
47 if (!sdf->HasElement(
"robotNamespace"))
49 ROS_INFO_NAMED(
"planar_move",
"PlanarMovePlugin missing <robotNamespace>, "
55 sdf->GetElement(
"robotNamespace")->Get<std::string>();
59 if (!sdf->HasElement(
"commandTopic"))
61 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <commandTopic>, "
67 command_topic_ = sdf->GetElement(
"commandTopic")->Get<std::string>();
71 if (!sdf->HasElement(
"odometryTopic"))
73 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <odometryTopic>, "
83 if (!sdf->HasElement(
"odometryFrame"))
85 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <odometryFrame>, "
95 if (!sdf->HasElement(
"robotBaseFrame"))
97 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <robotBaseFrame>, "
107 if (!sdf->HasElement(
"odometryRate"))
109 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <odometryRate>, "
118 if (!sdf->HasElement(
"cmdTimeout"))
120 ROS_WARN_NAMED(
"planar_move",
"PlanarMovePlugin (ns = %s) missing <cmdTimeout>, "
126 cmd_timeout_ = sdf->GetElement(
"cmdTimeout")->Get<
double>();
129 #if GAZEBO_MAJOR_VERSION >= 8
134 #if GAZEBO_MAJOR_VERSION >= 8
148 <<
"). A ROS node for Gazebo has not been initialized, "
149 <<
"unable to load plugin. Load the Gazebo system plugin "
150 <<
"'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
163 ros::SubscribeOptions::create<geometry_msgs::Twist>(
command_topic_, 1,
176 event::Events::ConnectWorldUpdateBegin(
184 #ifdef ENABLE_PROFILER
185 IGN_PROFILE(
"GazeboRosPlanarMove::UpdateChild");
186 IGN_PROFILE_BEGIN(
"fill ROS message");
188 boost::mutex::scoped_lock scoped_lock(
lock);
198 #if GAZEBO_MAJOR_VERSION >= 8
199 ignition::math::Pose3d pose =
parent_->WorldPose();
201 ignition::math::Pose3d pose =
parent_->GetWorldPose().Ign();
203 float yaw = pose.Rot().Yaw();
204 parent_->SetLinearVel(ignition::math::Vector3d(
205 x_ * cosf(yaw) -
y_ * sinf(yaw),
206 y_ * cosf(yaw) +
x_ * sinf(yaw),
208 parent_->SetAngularVel(ignition::math::Vector3d(0, 0,
rot_));
209 #ifdef ENABLE_PROFILER
213 #if GAZEBO_MAJOR_VERSION >= 8
214 common::Time current_time =
parent_->GetWorld()->SimTime();
216 common::Time current_time =
parent_->GetWorld()->GetSimTime();
218 double seconds_since_last_update =
221 #ifdef ENABLE_PROFILER
222 IGN_PROFILE_BEGIN(
"publishOdometry");
225 #ifdef ENABLE_PROFILER
243 const geometry_msgs::Twist::ConstPtr& cmd_msg)
245 boost::mutex::scoped_lock scoped_lock(
lock);
247 x_ = cmd_msg->linear.x;
248 y_ = cmd_msg->linear.y;
249 rot_ = cmd_msg->angular.z;
254 static const double timeout = 0.01;
266 std::string base_footprint_frame =
270 #if GAZEBO_MAJOR_VERSION >= 8
271 ignition::math::Pose3d pose = this->
parent_->WorldPose();
273 ignition::math::Pose3d pose = this->
parent_->GetWorldPose().Ign();
276 tf::Quaternion qt(pose.Rot().X(), pose.Rot().Y(), pose.Rot().Z(), pose.Rot().W());
277 tf::Vector3 vt(pose.Pos().X(), pose.Pos().Y(), pose.Pos().Z());
282 base_footprint_frame));
285 odom_.pose.pose.position.x = pose.Pos().X();
286 odom_.pose.pose.position.y = pose.Pos().Y();
288 odom_.pose.pose.orientation.x = pose.Rot().X();
289 odom_.pose.pose.orientation.y = pose.Rot().Y();
290 odom_.pose.pose.orientation.z = pose.Rot().Z();
291 odom_.pose.pose.orientation.w = pose.Rot().W();
292 odom_.pose.covariance[0] = 0.00001;
293 odom_.pose.covariance[7] = 0.00001;
294 odom_.pose.covariance[14] = 1000000000000.0;
295 odom_.pose.covariance[21] = 1000000000000.0;
296 odom_.pose.covariance[28] = 1000000000000.0;
297 odom_.pose.covariance[35] = 0.001;
300 ignition::math::Vector3d linear;
303 if (
rot_ > M_PI / step_time)
311 float current_yaw = pose.Rot().Yaw();
312 while (current_yaw < last_yaw - M_PI) current_yaw += 2 * M_PI;
313 while (current_yaw > last_yaw + M_PI) current_yaw -= 2 * M_PI;
314 float angular_diff = current_yaw - last_yaw;
315 odom_.twist.twist.angular.z = angular_diff / step_time;
320 float yaw = pose.Rot().Yaw();
321 odom_.twist.twist.linear.x = cosf(yaw) * linear.X() + sinf(yaw) * linear.Y();
322 odom_.twist.twist.linear.y = cosf(yaw) * linear.Y() - sinf(yaw) * linear.X();
324 odom_.header.stamp = current_time;
325 odom_.header.frame_id = odom_frame;
326 odom_.child_frame_id = base_footprint_frame;