#include <gazebo_ros_imu.h>
| Public Member Functions | |
| GazeboRosIMU () | |
| Constructor. | |
| void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) | 
| Load the controller. | |
| virtual | ~GazeboRosIMU () | 
| Destructor. | |
| Protected Member Functions | |
| virtual void | UpdateChild () | 
| Update the controller. | |
| Private Member Functions | |
| double | GaussianKernel (double mu, double sigma) | 
| Gaussian noise generator. | |
| void | IMUQueueThread () | 
| void | LoadThread () | 
| bool | ServiceCallback (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) | 
| call back when using service | |
| Private Attributes | |
| math::Vector3 | aeul_ | 
| math::Vector3 | apos_ | 
| boost::thread | callback_queue_thread_ | 
| boost::thread | deferred_load_thread_ | 
| std::string | frame_name_ | 
| store frame name | |
| double | gaussian_noise_ | 
| Gaussian noise. | |
| sensor_msgs::Imu | imu_msg_ | 
| ros message | |
| ros::CallbackQueue | imu_queue_ | 
| math::Pose | initial_pose_ | 
| : keep initial pose to offset orientation in imu message | |
| common::Time | last_time_ | 
| save last_time | |
| math::Vector3 | last_veul_ | 
| math::Vector3 | last_vpos_ | 
| physics::LinkPtr | link | 
| The link referred to by this plugin. | |
| std::string | link_name_ | 
| store link name | |
| boost::mutex | lock_ | 
| A mutex to lock access to fields that are used in message callbacks. | |
| math::Pose | offset_ | 
| allow specifying constant xyz and rpy offsets | |
| PubMultiQueue | pmq | 
| ros::Publisher | pub_ | 
| PubQueue< sensor_msgs::Imu >::Ptr | pub_Queue | 
| std::string | robot_namespace_ | 
| for setting ROS name space | |
| ros::NodeHandle * | rosnode_ | 
| pointer to ros node | |
| sdf::ElementPtr | sdf | 
| unsigned int | seed | 
| std::string | service_name_ | 
| ros::ServiceServer | srv_ | 
| std::string | topic_name_ | 
| topic name | |
| event::ConnectionPtr | update_connection_ | 
| double | update_rate_ | 
| physics::WorldPtr | world_ | 
| The parent World. | |
Definition at line 39 of file gazebo_ros_imu.h.
Constructor.
Definition at line 32 of file gazebo_ros_imu.cpp.
| gazebo::GazeboRosIMU::~GazeboRosIMU | ( | ) |  [virtual] | 
Destructor.
Definition at line 39 of file gazebo_ros_imu.cpp.
| double gazebo::GazeboRosIMU::GaussianKernel | ( | double | mu, | 
| double | sigma | ||
| ) |  [private] | 
Gaussian noise generator.
Definition at line 314 of file gazebo_ros_imu.cpp.
| void gazebo::GazeboRosIMU::IMUQueueThread | ( | ) |  [private] | 
Definition at line 338 of file gazebo_ros_imu.cpp.
| void gazebo::GazeboRosIMU::Load | ( | physics::ModelPtr | _parent, | 
| sdf::ElementPtr | _sdf | ||
| ) | 
Load the controller.
| node | XML config node | 
Definition at line 50 of file gazebo_ros_imu.cpp.
| void gazebo::GazeboRosIMU::LoadThread | ( | ) |  [private] | 
Definition at line 63 of file gazebo_ros_imu.cpp.
| bool gazebo::GazeboRosIMU::ServiceCallback | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Response & | res | ||
| ) |  [private] | 
call back when using service
Definition at line 196 of file gazebo_ros_imu.cpp.
| void gazebo::GazeboRosIMU::UpdateChild | ( | ) |  [protected, virtual] | 
Update the controller.
Definition at line 204 of file gazebo_ros_imu.cpp.
| math::Vector3 gazebo::GazeboRosIMU::aeul_  [private] | 
Definition at line 89 of file gazebo_ros_imu.h.
| math::Vector3 gazebo::GazeboRosIMU::apos_  [private] | 
Definition at line 88 of file gazebo_ros_imu.h.
| boost::thread gazebo::GazeboRosIMU::callback_queue_thread_  [private] | 
Definition at line 115 of file gazebo_ros_imu.h.
| boost::thread gazebo::GazeboRosIMU::deferred_load_thread_  [private] | 
Definition at line 123 of file gazebo_ros_imu.h.
| std::string gazebo::GazeboRosIMU::frame_name_  [private] | 
store frame name
Definition at line 72 of file gazebo_ros_imu.h.
| double gazebo::GazeboRosIMU::gaussian_noise_  [private] | 
Gaussian noise.
Definition at line 98 of file gazebo_ros_imu.h.
| sensor_msgs::Imu gazebo::GazeboRosIMU::imu_msg_  [private] | 
ros message
Definition at line 66 of file gazebo_ros_imu.h.
Definition at line 113 of file gazebo_ros_imu.h.
: keep initial pose to offset orientation in imu message
Definition at line 95 of file gazebo_ros_imu.h.
| common::Time gazebo::GazeboRosIMU::last_time_  [private] | 
save last_time
Definition at line 85 of file gazebo_ros_imu.h.
Definition at line 87 of file gazebo_ros_imu.h.
Definition at line 86 of file gazebo_ros_imu.h.
| physics::LinkPtr gazebo::GazeboRosIMU::link  [private] | 
The link referred to by this plugin.
Definition at line 58 of file gazebo_ros_imu.h.
| std::string gazebo::GazeboRosIMU::link_name_  [private] | 
store link name
Definition at line 69 of file gazebo_ros_imu.h.
| boost::mutex gazebo::GazeboRosIMU::lock_  [private] | 
A mutex to lock access to fields that are used in message callbacks.
Definition at line 82 of file gazebo_ros_imu.h.
| math::Pose gazebo::GazeboRosIMU::offset_  [private] | 
allow specifying constant xyz and rpy offsets
Definition at line 78 of file gazebo_ros_imu.h.
| PubMultiQueue gazebo::GazeboRosIMU::pmq  [private] | 
Definition at line 127 of file gazebo_ros_imu.h.
| ros::Publisher gazebo::GazeboRosIMU::pub_  [private] | 
Definition at line 62 of file gazebo_ros_imu.h.
| PubQueue<sensor_msgs::Imu>::Ptr gazebo::GazeboRosIMU::pub_Queue  [private] | 
Definition at line 63 of file gazebo_ros_imu.h.
| std::string gazebo::GazeboRosIMU::robot_namespace_  [private] | 
for setting ROS name space
Definition at line 104 of file gazebo_ros_imu.h.
| ros::NodeHandle* gazebo::GazeboRosIMU::rosnode_  [private] | 
pointer to ros node
Definition at line 61 of file gazebo_ros_imu.h.
| sdf::ElementPtr gazebo::GazeboRosIMU::sdf  [private] | 
Definition at line 121 of file gazebo_ros_imu.h.
| unsigned int gazebo::GazeboRosIMU::seed  [private] | 
Definition at line 124 of file gazebo_ros_imu.h.
| std::string gazebo::GazeboRosIMU::service_name_  [private] | 
Definition at line 111 of file gazebo_ros_imu.h.
| ros::ServiceServer gazebo::GazeboRosIMU::srv_  [private] | 
Definition at line 110 of file gazebo_ros_imu.h.
| std::string gazebo::GazeboRosIMU::topic_name_  [private] | 
topic name
Definition at line 75 of file gazebo_ros_imu.h.
Definition at line 118 of file gazebo_ros_imu.h.
| double gazebo::GazeboRosIMU::update_rate_  [private] | 
Definition at line 92 of file gazebo_ros_imu.h.
| physics::WorldPtr gazebo::GazeboRosIMU::world_  [private] | 
The parent World.
Definition at line 55 of file gazebo_ros_imu.h.