29 #ifndef HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H 30 #define HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H 38 #include <gazebo/common/Plugin.hh> 41 #include <boost/thread/mutex.hpp> 42 #include <sensor_msgs/Imu.h> 43 #include <std_srvs/Empty.h> 44 #include <hector_gazebo_plugins/SetBias.h> 48 #include <dynamic_reconfigure/server.h> 62 virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
93 #if (GAZEBO_MAJOR_VERSION >= 8) 108 #if (GAZEBO_MAJOR_VERSION >= 8) 111 ignition::math::Vector3d
accel;
112 ignition::math::Vector3d
rate;
113 ignition::math::Vector3d
gravity;
130 std_srvs::Empty::Response &res);
135 bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
136 bool SetRateBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res);
142 void CallbackQueueThread();
143 boost::thread callback_queue_thread_;
153 #endif // HECTOR_GAZEBO_PLUGINS_GAZEBO_ROS_IMU_H
ros::ServiceServer accelBiasService
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_yaw_
std::string namespace_
for setting ROS name space
bool SetAccelBiasCallback(hector_gazebo_plugins::SetBias::Request &req, hector_gazebo_plugins::SetBias::Response &res)
Bias service callbacks.
physics::WorldPtr world
The parent World.
boost::mutex lock
A mutex to lock access to fields that are used in message callbacks.
boost::shared_ptr< dynamic_reconfigure::Server< SensorModelConfig > > dynamic_reconfigure_server_rate_
std::string frame_id_
frame id
std::string link_name_
store link name
std::string topic_
topic name
event::ConnectionPtr updateConnection
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
ros::NodeHandle * node_handle_
pointer to ros node
virtual ~GazeboRosIMU()
Destructor.
sensor_msgs::Imu imuMsg
ros message
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
double GaussianKernel(double mu, double sigma)
Gaussian noise generator.
ros::ServiceServer rateBiasService
bool ServiceCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
call back when using service