#include <gazebo_odometry_plugin.h>
| Public Types | |
| typedef boost::array< double, 36 > | CovarianceMatrix | 
| typedef std::normal_distribution | NormalDistribution | 
| typedef std::deque< std::pair < int, gz_geometry_msgs::Odometry > > | OdometryQueue | 
| typedef std::uniform_real_distribution | UniformDistribution | 
| Public Member Functions | |
| GazeboOdometryPlugin () | |
| void | InitializeParams () | 
| void | Publish () | 
| ~GazeboOdometryPlugin () | |
| Protected Member Functions | |
| void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) | 
| void | OnUpdate (const common::UpdateInfo &) | 
| Private Member Functions | |
| void | CreatePubsAndSubs () | 
| Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required. | |
| void | QueueThread () | 
| Private Attributes | |
| NormalDistribution | angular_velocity_n_ [3] | 
| UniformDistribution | angular_velocity_u_ [3] | 
| NormalDistribution | attitude_n_ [3] | 
| UniformDistribution | attitude_u_ [3] | 
| gazebo::transport::PublisherPtr | broadcast_transform_pub_ | 
| Special-case publisher to publish stamped transforms with frame IDs. The ROS interface plugin (if present) will listen to this publisher and broadcast the transform using transform_broadcast(). | |
| boost::thread | callback_queue_thread_ | 
| std::string | child_frame_id_ | 
| cv::Mat | covariance_image_ | 
| double | covariance_image_scale_ | 
| int | gazebo_sequence_ | 
| NormalDistribution | linear_velocity_n_ [3] | 
| UniformDistribution | linear_velocity_u_ [3] | 
| physics::LinkPtr | link_ | 
| std::string | link_name_ | 
| int | measurement_delay_ | 
| int | measurement_divisor_ | 
| physics::ModelPtr | model_ | 
| std::string | namespace_ | 
| gazebo::transport::NodePtr | node_handle_ | 
| gazebo::transport::PublisherPtr | odometry_pub_ | 
| std::string | odometry_pub_topic_ | 
| OdometryQueue | odometry_queue_ | 
| int | odometry_sequence_ | 
| std::string | parent_frame_id_ | 
| physics::EntityPtr | parent_link_ | 
| CovarianceMatrix | pose_covariance_matrix_ | 
| gazebo::transport::PublisherPtr | pose_pub_ | 
| std::string | pose_pub_topic_ | 
| gazebo::transport::PublisherPtr | pose_with_covariance_stamped_pub_ | 
| std::string | pose_with_covariance_stamped_pub_topic_ | 
| NormalDistribution | position_n_ [3] | 
| gazebo::transport::PublisherPtr | position_stamped_pub_ | 
| std::string | position_stamped_pub_topic_ | 
| UniformDistribution | position_u_ [3] | 
| bool | pubs_and_subs_created_ | 
| Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate(). | |
| std::random_device | random_device_ | 
| std::mt19937 | random_generator_ | 
| gazebo::transport::PublisherPtr | transform_stamped_pub_ | 
| std::string | transform_stamped_pub_topic_ | 
| CovarianceMatrix | twist_covariance_matrix_ | 
| double | unknown_delay_ | 
| event::ConnectionPtr | updateConnection_ | 
| Pointer to the update event connection. | |
| physics::WorldPtr | world_ | 
Definition at line 61 of file gazebo_odometry_plugin.h.
| typedef boost::array<double, 36> gazebo::GazeboOdometryPlugin::CovarianceMatrix | 
Definition at line 66 of file gazebo_odometry_plugin.h.
| typedef std::normal_distribution gazebo::GazeboOdometryPlugin::NormalDistribution | 
Definition at line 63 of file gazebo_odometry_plugin.h.
| typedef std::deque<std::pair<int, gz_geometry_msgs::Odometry> > gazebo::GazeboOdometryPlugin::OdometryQueue | 
Definition at line 65 of file gazebo_odometry_plugin.h.
| typedef std::uniform_real_distribution gazebo::GazeboOdometryPlugin::UniformDistribution | 
Definition at line 64 of file gazebo_odometry_plugin.h.
| gazebo::GazeboOdometryPlugin::GazeboOdometryPlugin | ( | ) |  [inline] | 
Definition at line 68 of file gazebo_odometry_plugin.h.
Definition at line 45 of file gazebo_odometry_plugin.cpp.
| void gazebo::GazeboOdometryPlugin::CreatePubsAndSubs | ( | ) |  [private] | 
Creates all required publishers and subscribers, incl. routing of messages to/from ROS if required.
Call this once the first time OnUpdate() is called (can't be called from Load() because there is no guarantee GazeboRosInterfacePlugin has has loaded and listening to ConnectGazeboToRosTopic and ConnectRosToGazeboTopic messages).
Definition at line 515 of file gazebo_odometry_plugin.cpp.
| void gazebo::GazeboOdometryPlugin::Load | ( | physics::ModelPtr | _model, | 
| sdf::ElementPtr | _sdf | ||
| ) |  [protected] | 
Definition at line 48 of file gazebo_odometry_plugin.cpp.
| void gazebo::GazeboOdometryPlugin::OnUpdate | ( | const common::UpdateInfo & | _info | ) |  [protected] | 
Definition at line 236 of file gazebo_odometry_plugin.cpp.
| void gazebo::GazeboOdometryPlugin::QueueThread | ( | ) |  [private] | 
Definition at line 125 of file gazebo_odometry_plugin.h.
Definition at line 129 of file gazebo_odometry_plugin.h.
Definition at line 123 of file gazebo_odometry_plugin.h.
Definition at line 127 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::broadcast_transform_pub_  [private] | 
Special-case publisher to publish stamped transforms with frame IDs. The ROS interface plugin (if present) will listen to this publisher and broadcast the transform using transform_broadcast().
Definition at line 157 of file gazebo_odometry_plugin.h.
| boost::thread gazebo::GazeboOdometryPlugin::callback_queue_thread_  [private] | 
Definition at line 167 of file gazebo_odometry_plugin.h.
Definition at line 119 of file gazebo_odometry_plugin.h.
| cv::Mat gazebo::GazeboOdometryPlugin::covariance_image_  [private] | 
Definition at line 140 of file gazebo_odometry_plugin.h.
| double gazebo::GazeboOdometryPlugin::covariance_image_scale_  [private] | 
Definition at line 139 of file gazebo_odometry_plugin.h.
Definition at line 136 of file gazebo_odometry_plugin.h.
Definition at line 124 of file gazebo_odometry_plugin.h.
Definition at line 128 of file gazebo_odometry_plugin.h.
| physics::LinkPtr gazebo::GazeboOdometryPlugin::link_  [private] | 
Definition at line 161 of file gazebo_odometry_plugin.h.
Definition at line 120 of file gazebo_odometry_plugin.h.
Definition at line 134 of file gazebo_odometry_plugin.h.
Definition at line 135 of file gazebo_odometry_plugin.h.
| physics::ModelPtr gazebo::GazeboOdometryPlugin::model_  [private] | 
Definition at line 160 of file gazebo_odometry_plugin.h.
Definition at line 112 of file gazebo_odometry_plugin.h.
| gazebo::transport::NodePtr gazebo::GazeboOdometryPlugin::node_handle_  [private] | 
Definition at line 145 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::odometry_pub_  [private] | 
Definition at line 151 of file gazebo_odometry_plugin.h.
Definition at line 117 of file gazebo_odometry_plugin.h.
Definition at line 110 of file gazebo_odometry_plugin.h.
Definition at line 137 of file gazebo_odometry_plugin.h.
Definition at line 118 of file gazebo_odometry_plugin.h.
| physics::EntityPtr gazebo::GazeboOdometryPlugin::parent_link_  [private] | 
Definition at line 162 of file gazebo_odometry_plugin.h.
Definition at line 131 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::pose_pub_  [private] | 
Definition at line 147 of file gazebo_odometry_plugin.h.
Definition at line 113 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::pose_with_covariance_stamped_pub_  [private] | 
Definition at line 148 of file gazebo_odometry_plugin.h.
Definition at line 114 of file gazebo_odometry_plugin.h.
Definition at line 122 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::position_stamped_pub_  [private] | 
Definition at line 149 of file gazebo_odometry_plugin.h.
Definition at line 115 of file gazebo_odometry_plugin.h.
Definition at line 126 of file gazebo_odometry_plugin.h.
| bool gazebo::GazeboOdometryPlugin::pubs_and_subs_created_  [private] | 
Flag that is set to true once CreatePubsAndSubs() is called, used to prevent CreatePubsAndSubs() from be called on every OnUpdate().
Definition at line 102 of file gazebo_odometry_plugin.h.
| std::random_device gazebo::GazeboOdometryPlugin::random_device_  [private] | 
Definition at line 142 of file gazebo_odometry_plugin.h.
| std::mt19937 gazebo::GazeboOdometryPlugin::random_generator_  [private] | 
Definition at line 143 of file gazebo_odometry_plugin.h.
| gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::transform_stamped_pub_  [private] | 
Definition at line 150 of file gazebo_odometry_plugin.h.
Definition at line 116 of file gazebo_odometry_plugin.h.
Definition at line 132 of file gazebo_odometry_plugin.h.
| double gazebo::GazeboOdometryPlugin::unknown_delay_  [private] | 
Definition at line 138 of file gazebo_odometry_plugin.h.
Pointer to the update event connection.
Definition at line 165 of file gazebo_odometry_plugin.h.
| physics::WorldPtr gazebo::GazeboOdometryPlugin::world_  [private] | 
Definition at line 159 of file gazebo_odometry_plugin.h.