30 #include <gazebo/common/Events.hh> 31 #include <gazebo/physics/physics.hh> 40 #include <geometry_msgs/PoseStamped.h> 42 #endif // DEBUG_OUTPUT 62 callback_queue_thread_.join();
72 world = _model->GetWorld();
75 if (_sdf->HasElement(
"robotNamespace"))
76 namespace_ = _sdf->GetElement(
"robotNamespace")->GetValue()->GetAsString();
80 if (_sdf->HasElement(
"bodyName"))
82 link_name_ = _sdf->GetElement(
"bodyName")->GetValue()->GetAsString();
87 link = _model->GetLink();
102 if (_sdf->HasElement(
"frameId"))
103 frame_id_ = _sdf->GetElement(
"frameId")->GetValue()->GetAsString();
105 if (_sdf->HasElement(
"topicName"))
106 topic_ = _sdf->GetElement(
"topicName")->GetValue()->GetAsString();
108 if (_sdf->HasElement(
"biasTopicName"))
109 bias_topic_ = _sdf->GetElement(
"biasTopicName")->GetValue()->GetAsString();
113 if (_sdf->HasElement(
"serviceName"))
114 serviceName = _sdf->GetElement(
"serviceName")->GetValue()->GetAsString();
123 if (_sdf->HasElement(
"gaussianNoise")) {
124 double gaussianNoise;
125 if (_sdf->GetElement(
"gaussianNoise")->GetValue()->Get(gaussianNoise) && gaussianNoise != 0.0) {
131 if (_sdf->HasElement(
"xyzOffset")) {
132 #if (GAZEBO_MAJOR_VERSION >= 8) 133 this->
offset_.Pos() = _sdf->Get<ignition::math::Vector3d>(
"xyzOffset");
135 this->
offset_.pos = _sdf->Get<math::Vector3>(
"xyzOffset");
138 ROS_INFO(
"imu plugin missing <xyzOffset>, defaults to 0s");
139 #if (GAZEBO_MAJOR_VERSION >= 8) 140 this->
offset_.Pos() = ignition::math::Vector3d(0, 0, 0);
142 this->
offset_.pos = math::Vector3(0, 0, 0);
146 if (_sdf->HasElement(
"rpyOffset")) {
147 #if (GAZEBO_MAJOR_VERSION >= 8) 148 this->
offset_.Rot() = _sdf->Get<ignition::math::Quaterniond>(
"rpyOffset");
150 this->
offset_.rot = _sdf->Get<math::Vector3>(
"rpyOffset");
153 ROS_INFO(
"imu plugin missing <rpyOffset>, defaults to 0s");
154 #if (GAZEBO_MAJOR_VERSION >= 8) 155 this->
offset_.Rot() = ignition::math::Quaterniond(0, 0, 0);
157 this->
offset_.rot = math::Vector3(0, 0, 0);
162 #if (GAZEBO_MAJOR_VERSION >= 8) 181 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. " 182 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package.");
195 debugPublisher = rosnode_->advertise<geometry_msgs::PoseStamped>(
topic_ +
"/pose", 10);
196 #endif // DEBUG_OUTPUT 206 if (!topic_.empty()) {
217 callback_queue_thread_ = boost::thread( boost::bind( &GazeboRosIMU::CallbackQueueThread,
this ) );
231 #if (GAZEBO_MAJOR_VERSION >= 8) 247 std_srvs::Empty::Response &res)
249 boost::mutex::scoped_lock scoped_lock(
lock);
250 #if (GAZEBO_MAJOR_VERSION >= 8) 260 boost::mutex::scoped_lock scoped_lock(
lock);
261 #if (GAZEBO_MAJOR_VERSION >= 8) 262 accelModel.
reset(ignition::math::Vector3d(req.bias.x, req.bias.y, req.bias.z));
271 boost::mutex::scoped_lock scoped_lock(
lock);
272 #if (GAZEBO_MAJOR_VERSION >= 8) 273 rateModel.
reset(ignition::math::Vector3d(req.bias.x, req.bias.y, req.bias.z));
275 rateModel.
reset(math::Vector3(req.bias.x, req.bias.y, req.bias.z));
285 #if (GAZEBO_MAJOR_VERSION >= 8) 286 common::Time cur_time =
world->SimTime();
288 common::Time cur_time =
world->GetSimTime();
291 boost::mutex::scoped_lock scoped_lock(
lock);
294 #if (GAZEBO_MAJOR_VERSION >= 8) 295 ignition::math::Pose3d pose =
link->WorldPose();
297 ignition::math::Quaterniond rot = this->
offset_.Rot() * pose.Rot();
299 math::Pose pose =
link->GetWorldPose();
301 math::Quaternion rot = this->
offset_.rot * pose.rot;
306 #if (GAZEBO_MAJOR_VERSION >= 8) 308 double gravity_length =
gravity.Length();
312 double gravity_length = gravity.GetLength();
313 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"gravity_world = [%g %g %g]", gravity.x, gravity.y, gravity.z);
319 #if (GAZEBO_MAJOR_VERSION >= 8) 320 ignition::math::Vector3d temp =
link->WorldLinearVel();
322 math::Vector3 temp =
link->GetWorldLinearVel();
324 if (dt > 0.0)
accel = rot.RotateVectorReverse((temp -
velocity) / dt - gravity);
330 #if (GAZEBO_MAJOR_VERSION >= 8) 331 ignition::math::Quaterniond delta = this->
orientation.Inverse() * rot;
333 math::Quaternion delta = this->
orientation.GetInverse() * rot;
337 #if (GAZEBO_MAJOR_VERSION >= 8) 339 * (2.0 * acos(std::max(std::min(delta.W(), 1.0), -1.0)) * ignition::math::Vector3d(delta.X(), delta.Y(), delta.Z()).Normalize() / dt);
342 * (2.0 * acos(std::max(std::min(delta.w, 1.0), -1.0)) * math::Vector3(delta.x, delta.y, delta.z).Normalize() / dt);
350 #if (GAZEBO_MAJOR_VERSION >= 8) 351 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"Current bias errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
355 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"Scale errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
360 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"Current bias errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
364 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"Scale errors: accel = [%g %g %g], rate = [%g %g %g], yaw = %g",
371 #if (GAZEBO_MAJOR_VERSION >= 8) 374 ignition::math::Quaterniond orientationError(
375 ignition::math::Quaterniond(cos(yawError/2), 0.0, 0.0, sin(yawError/2)) *
376 ignition::math::Quaterniond(1.0, 0.5 * accelDrift.Y() / gravity_length, 0.5 * -accelDrift.X() / gravity_length, 0.0)
381 math::Quaternion orientationError(
382 math::Quaternion(cos(yawError/2), 0.0, 0.0, sin(yawError/2)) *
383 math::Quaternion(1.0, 0.5 * accelDrift.y / gravity_length, 0.5 * -accelDrift.x / gravity_length, 0.0)
386 orientationError.Normalize();
387 rot = orientationError * rot;
391 imuMsg.header.stamp.sec = cur_time.sec;
392 imuMsg.header.stamp.nsec = cur_time.nsec;
395 #if (GAZEBO_MAJOR_VERSION >= 8) 396 imuMsg.orientation.x = rot.X();
397 imuMsg.orientation.y = rot.Y();
398 imuMsg.orientation.z = rot.Z();
399 imuMsg.orientation.w = rot.W();
401 imuMsg.orientation.x = rot.x;
402 imuMsg.orientation.y = rot.y;
403 imuMsg.orientation.z = rot.z;
404 imuMsg.orientation.w = rot.w;
408 #if (GAZEBO_MAJOR_VERSION >= 8) 419 #if (GAZEBO_MAJOR_VERSION >= 8) 431 if (gravity_length > 0.0) {
432 #if (GAZEBO_MAJOR_VERSION >= 8) 440 imuMsg.orientation_covariance[0] = -1;
441 imuMsg.orientation_covariance[4] = -1;
446 ROS_DEBUG_NAMED(
"gazebo_ros_imu",
"Publishing IMU data at t = %f", cur_time.Double());
451 #if (GAZEBO_MAJOR_VERSION >= 8) 452 biasMsg.orientation.x = orientationError.X();
453 biasMsg.orientation.y = orientationError.Y();
454 biasMsg.orientation.z = orientationError.Z();
455 biasMsg.orientation.w = orientationError.W();
463 biasMsg.orientation.x = orientationError.x;
464 biasMsg.orientation.y = orientationError.y;
465 biasMsg.orientation.z = orientationError.z;
466 biasMsg.orientation.w = orientationError.w;
479 if (debugPublisher) {
480 geometry_msgs::PoseStamped debugPose;
481 debugPose.header =
imuMsg.header;
482 debugPose.header.frame_id =
"/map";
483 debugPose.pose.orientation.w =
imuMsg.orientation.w;
484 debugPose.pose.orientation.x =
imuMsg.orientation.x;
485 debugPose.pose.orientation.y =
imuMsg.orientation.y;
486 debugPose.pose.orientation.z =
imuMsg.orientation.z;
487 #if (GAZEBO_MAJOR_VERSION >= 8) 488 ignition::math::Pose3d pose =
link->WorldPose();
489 debugPose.pose.position.x = pose.Pos().X();
490 debugPose.pose.position.y = pose.Pos().Y();
491 debugPose.pose.position.z = pose.Pos().Z();
493 math::Pose pose =
link->GetWorldPose();
494 debugPose.pose.position.x = pose.pos.x;
495 debugPose.pose.position.y = pose.pos.y;
496 debugPose.pose.position.z = pose.pos.z;
498 debugPublisher.
publish(debugPose);
500 #endif // DEBUG_OUTPUT 504 void GazeboRosIMU::CallbackQueueThread()
506 static const double timeout = 0.01;
508 while (rosnode_->ok())
ros::ServiceServer accelBiasService
virtual T update(double dt)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_yaw_
virtual void Load(physics::WorldPtr _world, sdf::ElementPtr _sdf, const std::string &_prefix="update")
std::string namespace_
for setting ROS name space
void publish(const boost::shared_ptr< M > &message) const
bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
Bias service callbacks.
virtual void Load(sdf::ElementPtr _sdf, const std::string &prefix=std::string())
physics::WorldPtr world
The parent World.
boost::mutex lock
A mutex to lock access to fields that are used in message callbacks.
ROSCPP_DECL bool isInitialized()
virtual T getCurrentBias() const
virtual event::ConnectionPtr Connect(const boost::function< void()> &_subscriber, bool connectToWorldUpdateBegin=true)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_rate_
std::string frame_id_
frame id
std::string link_name_
store link name
#define ROS_DEBUG_NAMED(name,...)
std::string topic_
topic name
#define ROS_FATAL_STREAM(args)
virtual void Disconnect(event::ConnectionPtr const &_c=event::ConnectionPtr())
virtual void dynamicReconfigureCallback(SensorModelConfig &config, uint32_t level)
event::ConnectionPtr updateConnection
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
common::Time getTimeSinceLastUpdate() const
ros::NodeHandle * node_handle_
pointer to ros node
virtual ~GazeboRosIMU()
Destructor.
sensor_msgs::Imu imuMsg
ros message
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_accel_
GazeboRosIMU()
Constructor.
bool SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
math::Pose offset_
allow specifying constant xyz and rpy offsets
SensorModel3 accelModel
Sensor models.
physics::LinkPtr link
The link referred to by this plugin.
math::Quaternion orientation
save current body/physics state
virtual const T & getScaleError() const
ros::ServiceServer rateBiasService
bool ServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
call back when using service