#include <gazebo_ros_imu.h>
Definition at line 39 of file gazebo_ros_imu.h.
◆ GazeboRosIMU()
gazebo::GazeboRosIMU::GazeboRosIMU |
( |
| ) |
|
◆ ~GazeboRosIMU()
gazebo::GazeboRosIMU::~GazeboRosIMU |
( |
| ) |
|
|
virtual |
◆ GaussianKernel()
double gazebo::GazeboRosIMU::GaussianKernel |
( |
double |
mu, |
|
|
double |
sigma |
|
) |
| |
|
private |
◆ IMUQueueThread()
void gazebo::GazeboRosIMU::IMUQueueThread |
( |
| ) |
|
|
private |
◆ Load()
void gazebo::GazeboRosIMU::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
◆ LoadThread()
void gazebo::GazeboRosIMU::LoadThread |
( |
| ) |
|
|
private |
◆ ServiceCallback()
bool gazebo::GazeboRosIMU::ServiceCallback |
( |
std_srvs::Empty::Request & |
req, |
|
|
std_srvs::Empty::Response & |
res |
|
) |
| |
|
private |
◆ UpdateChild()
void gazebo::GazeboRosIMU::UpdateChild |
( |
| ) |
|
|
protectedvirtual |
Update the controller.
- Todo:
- : let user set separate linear and angular covariance values.
- Todo:
- : apply appropriate rotations from frame_pose
Definition at line 217 of file gazebo_ros_imu.cpp.
◆ aeul_
ignition::math::Vector3d gazebo::GazeboRosIMU::aeul_ |
|
private |
◆ apos_
ignition::math::Vector3d gazebo::GazeboRosIMU::apos_ |
|
private |
◆ callback_queue_thread_
boost::thread gazebo::GazeboRosIMU::callback_queue_thread_ |
|
private |
◆ deferred_load_thread_
boost::thread gazebo::GazeboRosIMU::deferred_load_thread_ |
|
private |
◆ frame_name_
std::string gazebo::GazeboRosIMU::frame_name_ |
|
private |
◆ gaussian_noise_
double gazebo::GazeboRosIMU::gaussian_noise_ |
|
private |
◆ imu_msg_
sensor_msgs::Imu gazebo::GazeboRosIMU::imu_msg_ |
|
private |
◆ imu_queue_
◆ initial_pose_
ignition::math::Pose3d gazebo::GazeboRosIMU::initial_pose_ |
|
private |
: keep initial pose to offset orientation in imu message
Definition at line 95 of file gazebo_ros_imu.h.
◆ last_time_
common::Time gazebo::GazeboRosIMU::last_time_ |
|
private |
◆ last_veul_
ignition::math::Vector3d gazebo::GazeboRosIMU::last_veul_ |
|
private |
◆ last_vpos_
ignition::math::Vector3d gazebo::GazeboRosIMU::last_vpos_ |
|
private |
◆ link
physics::LinkPtr gazebo::GazeboRosIMU::link |
|
private |
◆ link_name_
std::string gazebo::GazeboRosIMU::link_name_ |
|
private |
◆ lock_
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.
◆ offset_
ignition::math::Pose3d gazebo::GazeboRosIMU::offset_ |
|
private |
allow specifying constant xyz and rpy offsets
Definition at line 78 of file gazebo_ros_imu.h.
◆ pmq
◆ pub_
◆ pub_Queue
PubQueue<sensor_msgs::Imu>::Ptr gazebo::GazeboRosIMU::pub_Queue |
|
private |
◆ robot_namespace_
std::string gazebo::GazeboRosIMU::robot_namespace_ |
|
private |
◆ rosnode_
◆ sdf
sdf::ElementPtr gazebo::GazeboRosIMU::sdf |
|
private |
◆ service_name_
std::string gazebo::GazeboRosIMU::service_name_ |
|
private |
◆ srv_
◆ topic_name_
std::string gazebo::GazeboRosIMU::topic_name_ |
|
private |
◆ update_connection_
◆ update_rate_
double gazebo::GazeboRosIMU::update_rate_ |
|
private |
◆ world_
physics::WorldPtr gazebo::GazeboRosIMU::world_ |
|
private |
The documentation for this class was generated from the following files: