Public Types | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::GazeboOdometryPlugin Class Reference

#include <gazebo_odometry_plugin.h>

Inheritance diagram for gazebo::GazeboOdometryPlugin:
Inheritance graph
[legend]

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. More...
 
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(). More...
 
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(). More...
 
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. More...
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 61 of file gazebo_odometry_plugin.h.

Member Typedef Documentation

◆ CovarianceMatrix

typedef boost::array<double, 36> gazebo::GazeboOdometryPlugin::CovarianceMatrix

Definition at line 66 of file gazebo_odometry_plugin.h.

◆ NormalDistribution

typedef std::normal_distribution gazebo::GazeboOdometryPlugin::NormalDistribution

Definition at line 63 of file gazebo_odometry_plugin.h.

◆ OdometryQueue

typedef std::deque<std::pair<int, gz_geometry_msgs::Odometry> > gazebo::GazeboOdometryPlugin::OdometryQueue

Definition at line 65 of file gazebo_odometry_plugin.h.

◆ UniformDistribution

typedef std::uniform_real_distribution gazebo::GazeboOdometryPlugin::UniformDistribution

Definition at line 64 of file gazebo_odometry_plugin.h.

Constructor & Destructor Documentation

◆ GazeboOdometryPlugin()

gazebo::GazeboOdometryPlugin::GazeboOdometryPlugin ( )
inline

Definition at line 68 of file gazebo_odometry_plugin.h.

◆ ~GazeboOdometryPlugin()

gazebo::GazeboOdometryPlugin::~GazeboOdometryPlugin ( )

Definition at line 45 of file gazebo_odometry_plugin.cpp.

Member Function Documentation

◆ CreatePubsAndSubs()

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.

◆ InitializeParams()

void gazebo::GazeboOdometryPlugin::InitializeParams ( )

◆ Load()

void gazebo::GazeboOdometryPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protected

Definition at line 48 of file gazebo_odometry_plugin.cpp.

◆ OnUpdate()

void gazebo::GazeboOdometryPlugin::OnUpdate ( const common::UpdateInfo &  _info)
protected

Definition at line 236 of file gazebo_odometry_plugin.cpp.

◆ Publish()

void gazebo::GazeboOdometryPlugin::Publish ( )

◆ QueueThread()

void gazebo::GazeboOdometryPlugin::QueueThread ( )
private

Member Data Documentation

◆ angular_velocity_n_

NormalDistribution gazebo::GazeboOdometryPlugin::angular_velocity_n_[3]
private

Definition at line 125 of file gazebo_odometry_plugin.h.

◆ angular_velocity_u_

UniformDistribution gazebo::GazeboOdometryPlugin::angular_velocity_u_[3]
private

Definition at line 129 of file gazebo_odometry_plugin.h.

◆ attitude_n_

NormalDistribution gazebo::GazeboOdometryPlugin::attitude_n_[3]
private

Definition at line 123 of file gazebo_odometry_plugin.h.

◆ attitude_u_

UniformDistribution gazebo::GazeboOdometryPlugin::attitude_u_[3]
private

Definition at line 127 of file gazebo_odometry_plugin.h.

◆ broadcast_transform_pub_

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.

◆ callback_queue_thread_

boost::thread gazebo::GazeboOdometryPlugin::callback_queue_thread_
private

Definition at line 167 of file gazebo_odometry_plugin.h.

◆ child_frame_id_

std::string gazebo::GazeboOdometryPlugin::child_frame_id_
private

Definition at line 119 of file gazebo_odometry_plugin.h.

◆ covariance_image_

cv::Mat gazebo::GazeboOdometryPlugin::covariance_image_
private

Definition at line 140 of file gazebo_odometry_plugin.h.

◆ covariance_image_scale_

double gazebo::GazeboOdometryPlugin::covariance_image_scale_
private

Definition at line 139 of file gazebo_odometry_plugin.h.

◆ gazebo_sequence_

int gazebo::GazeboOdometryPlugin::gazebo_sequence_
private

Definition at line 136 of file gazebo_odometry_plugin.h.

◆ linear_velocity_n_

NormalDistribution gazebo::GazeboOdometryPlugin::linear_velocity_n_[3]
private

Definition at line 124 of file gazebo_odometry_plugin.h.

◆ linear_velocity_u_

UniformDistribution gazebo::GazeboOdometryPlugin::linear_velocity_u_[3]
private

Definition at line 128 of file gazebo_odometry_plugin.h.

◆ link_

physics::LinkPtr gazebo::GazeboOdometryPlugin::link_
private

Definition at line 161 of file gazebo_odometry_plugin.h.

◆ link_name_

std::string gazebo::GazeboOdometryPlugin::link_name_
private

Definition at line 120 of file gazebo_odometry_plugin.h.

◆ measurement_delay_

int gazebo::GazeboOdometryPlugin::measurement_delay_
private

Definition at line 134 of file gazebo_odometry_plugin.h.

◆ measurement_divisor_

int gazebo::GazeboOdometryPlugin::measurement_divisor_
private

Definition at line 135 of file gazebo_odometry_plugin.h.

◆ model_

physics::ModelPtr gazebo::GazeboOdometryPlugin::model_
private

Definition at line 160 of file gazebo_odometry_plugin.h.

◆ namespace_

std::string gazebo::GazeboOdometryPlugin::namespace_
private

Definition at line 112 of file gazebo_odometry_plugin.h.

◆ node_handle_

gazebo::transport::NodePtr gazebo::GazeboOdometryPlugin::node_handle_
private

Definition at line 145 of file gazebo_odometry_plugin.h.

◆ odometry_pub_

gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::odometry_pub_
private

Definition at line 151 of file gazebo_odometry_plugin.h.

◆ odometry_pub_topic_

std::string gazebo::GazeboOdometryPlugin::odometry_pub_topic_
private

Definition at line 117 of file gazebo_odometry_plugin.h.

◆ odometry_queue_

OdometryQueue gazebo::GazeboOdometryPlugin::odometry_queue_
private

Definition at line 110 of file gazebo_odometry_plugin.h.

◆ odometry_sequence_

int gazebo::GazeboOdometryPlugin::odometry_sequence_
private

Definition at line 137 of file gazebo_odometry_plugin.h.

◆ parent_frame_id_

std::string gazebo::GazeboOdometryPlugin::parent_frame_id_
private

Definition at line 118 of file gazebo_odometry_plugin.h.

◆ parent_link_

physics::EntityPtr gazebo::GazeboOdometryPlugin::parent_link_
private

Definition at line 162 of file gazebo_odometry_plugin.h.

◆ pose_covariance_matrix_

CovarianceMatrix gazebo::GazeboOdometryPlugin::pose_covariance_matrix_
private

Definition at line 131 of file gazebo_odometry_plugin.h.

◆ pose_pub_

gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::pose_pub_
private

Definition at line 147 of file gazebo_odometry_plugin.h.

◆ pose_pub_topic_

std::string gazebo::GazeboOdometryPlugin::pose_pub_topic_
private

Definition at line 113 of file gazebo_odometry_plugin.h.

◆ pose_with_covariance_stamped_pub_

gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::pose_with_covariance_stamped_pub_
private

Definition at line 148 of file gazebo_odometry_plugin.h.

◆ pose_with_covariance_stamped_pub_topic_

std::string gazebo::GazeboOdometryPlugin::pose_with_covariance_stamped_pub_topic_
private

Definition at line 114 of file gazebo_odometry_plugin.h.

◆ position_n_

NormalDistribution gazebo::GazeboOdometryPlugin::position_n_[3]
private

Definition at line 122 of file gazebo_odometry_plugin.h.

◆ position_stamped_pub_

gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::position_stamped_pub_
private

Definition at line 149 of file gazebo_odometry_plugin.h.

◆ position_stamped_pub_topic_

std::string gazebo::GazeboOdometryPlugin::position_stamped_pub_topic_
private

Definition at line 115 of file gazebo_odometry_plugin.h.

◆ position_u_

UniformDistribution gazebo::GazeboOdometryPlugin::position_u_[3]
private

Definition at line 126 of file gazebo_odometry_plugin.h.

◆ pubs_and_subs_created_

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.

◆ random_device_

std::random_device gazebo::GazeboOdometryPlugin::random_device_
private

Definition at line 142 of file gazebo_odometry_plugin.h.

◆ random_generator_

std::mt19937 gazebo::GazeboOdometryPlugin::random_generator_
private

Definition at line 143 of file gazebo_odometry_plugin.h.

◆ transform_stamped_pub_

gazebo::transport::PublisherPtr gazebo::GazeboOdometryPlugin::transform_stamped_pub_
private

Definition at line 150 of file gazebo_odometry_plugin.h.

◆ transform_stamped_pub_topic_

std::string gazebo::GazeboOdometryPlugin::transform_stamped_pub_topic_
private

Definition at line 116 of file gazebo_odometry_plugin.h.

◆ twist_covariance_matrix_

CovarianceMatrix gazebo::GazeboOdometryPlugin::twist_covariance_matrix_
private

Definition at line 132 of file gazebo_odometry_plugin.h.

◆ unknown_delay_

double gazebo::GazeboOdometryPlugin::unknown_delay_
private

Definition at line 138 of file gazebo_odometry_plugin.h.

◆ updateConnection_

event::ConnectionPtr gazebo::GazeboOdometryPlugin::updateConnection_
private

Pointer to the update event connection.

Definition at line 165 of file gazebo_odometry_plugin.h.

◆ world_

physics::WorldPtr gazebo::GazeboOdometryPlugin::world_
private

Definition at line 159 of file gazebo_odometry_plugin.h.


The documentation for this class was generated from the following files:


rotors_gazebo_plugins
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:39:04