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

#include <gazebo_ros_p3d.h>

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

Public Member Functions

 GazeboRosP3D ()
 Constructor. More...
 
void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 Load the controller. More...
 
virtual ~GazeboRosP3D ()
 Destructor. More...
 

Protected Member Functions

virtual void UpdateChild ()
 Update the controller. More...
 

Private Member Functions

double GaussianKernel (double mu, double sigma)
 Gaussian noise generator. More...
 
void P3DQueueThread ()
 

Private Attributes

ignition::math::Vector3d aeul_
 
ignition::math::Vector3d apos_
 
boost::thread callback_queue_thread_
 
ignition::math::Vector3d frame_aeul_
 
ignition::math::Vector3d frame_apos_
 
std::string frame_name_
 frame transform name, should match link name FIXME: extract link name directly? More...
 
double gaussian_noise_
 Gaussian noise. More...
 
ignition::math::Vector3d last_frame_veul_
 
ignition::math::Vector3d last_frame_vpos_
 
common::Time last_time_
 save last_time More...
 
ignition::math::Vector3d last_veul_
 
ignition::math::Vector3d last_vpos_
 
physics::LinkPtr link_
 The parent Model. More...
 
std::string link_name_
 store bodyname More...
 
boost::mutex lock
 mutex to lock access to fields used in message callbacks More...
 
physics::ModelPtr model_
 
ignition::math::Pose3d offset_
 allow specifying constant xyz and rpy offsets More...
 
ros::CallbackQueue p3d_queue_
 
PubMultiQueue pmq
 
nav_msgs::Odometry pose_msg_
 ros message More...
 
ros::Publisher pub_
 
PubQueue< nav_msgs::Odometry >::Ptr pub_Queue
 
physics::LinkPtr reference_link_
 The body of the frame to display pose, twist. More...
 
std::string robot_namespace_
 for setting ROS name space More...
 
ros::NodeHandlerosnode_
 pointer to ros node More...
 
unsigned int seed
 
std::string tf_frame_name_
 
std::string topic_name_
 topic name More...
 
event::ConnectionPtr update_connection_
 
double update_rate_
 
physics::WorldPtr world_
 

Detailed Description

Definition at line 48 of file gazebo_ros_p3d.h.

Constructor & Destructor Documentation

gazebo::GazeboRosP3D::GazeboRosP3D ( )

Constructor.

Definition at line 30 of file gazebo_ros_p3d.cpp.

gazebo::GazeboRosP3D::~GazeboRosP3D ( )
virtual

Destructor.

Definition at line 37 of file gazebo_ros_p3d.cpp.

Member Function Documentation

double gazebo::GazeboRosP3D::GaussianKernel ( double  mu,
double  sigma 
)
private

Gaussian noise generator.

Definition at line 364 of file gazebo_ros_p3d.cpp.

void gazebo::GazeboRosP3D::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)

Load the controller.

Definition at line 50 of file gazebo_ros_p3d.cpp.

void gazebo::GazeboRosP3D::P3DQueueThread ( )
private

Definition at line 388 of file gazebo_ros_p3d.cpp.

void gazebo::GazeboRosP3D::UpdateChild ( )
protectedvirtual

Update the controller.

Todo:
: let user set separate linear and angular covariance values.

Definition at line 213 of file gazebo_ros_p3d.cpp.

Member Data Documentation

ignition::math::Vector3d gazebo::GazeboRosP3D::aeul_
private

Definition at line 102 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::apos_
private

Definition at line 101 of file gazebo_ros_p3d.h.

boost::thread gazebo::GazeboRosP3D::callback_queue_thread_
private

Definition at line 122 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::frame_aeul_
private

Definition at line 106 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::frame_apos_
private

Definition at line 105 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::frame_name_
private

frame transform name, should match link name FIXME: extract link name directly?

Definition at line 88 of file gazebo_ros_p3d.h.

double gazebo::GazeboRosP3D::gaussian_noise_
private

Gaussian noise.

Definition at line 112 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::last_frame_veul_
private

Definition at line 104 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::last_frame_vpos_
private

Definition at line 103 of file gazebo_ros_p3d.h.

common::Time gazebo::GazeboRosP3D::last_time_
private

save last_time

Definition at line 98 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::last_veul_
private

Definition at line 100 of file gazebo_ros_p3d.h.

ignition::math::Vector3d gazebo::GazeboRosP3D::last_vpos_
private

Definition at line 99 of file gazebo_ros_p3d.h.

physics::LinkPtr gazebo::GazeboRosP3D::link_
private

The parent Model.

Definition at line 66 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::link_name_
private

store bodyname

Definition at line 81 of file gazebo_ros_p3d.h.

boost::mutex gazebo::GazeboRosP3D::lock
private

mutex to lock access to fields used in message callbacks

Definition at line 95 of file gazebo_ros_p3d.h.

physics::ModelPtr gazebo::GazeboRosP3D::model_
private

Definition at line 63 of file gazebo_ros_p3d.h.

ignition::math::Pose3d gazebo::GazeboRosP3D::offset_
private

allow specifying constant xyz and rpy offsets

Definition at line 92 of file gazebo_ros_p3d.h.

ros::CallbackQueue gazebo::GazeboRosP3D::p3d_queue_
private

Definition at line 120 of file gazebo_ros_p3d.h.

PubMultiQueue gazebo::GazeboRosP3D::pmq
private

Definition at line 130 of file gazebo_ros_p3d.h.

nav_msgs::Odometry gazebo::GazeboRosP3D::pose_msg_
private

ros message

Definition at line 78 of file gazebo_ros_p3d.h.

ros::Publisher gazebo::GazeboRosP3D::pub_
private

Definition at line 74 of file gazebo_ros_p3d.h.

PubQueue<nav_msgs::Odometry>::Ptr gazebo::GazeboRosP3D::pub_Queue
private

Definition at line 75 of file gazebo_ros_p3d.h.

physics::LinkPtr gazebo::GazeboRosP3D::reference_link_
private

The body of the frame to display pose, twist.

Definition at line 69 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::robot_namespace_
private

for setting ROS name space

Definition at line 118 of file gazebo_ros_p3d.h.

ros::NodeHandle* gazebo::GazeboRosP3D::rosnode_
private

pointer to ros node

Definition at line 73 of file gazebo_ros_p3d.h.

unsigned int gazebo::GazeboRosP3D::seed
private

Definition at line 127 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::tf_frame_name_
private

Definition at line 89 of file gazebo_ros_p3d.h.

std::string gazebo::GazeboRosP3D::topic_name_
private

topic name

Definition at line 84 of file gazebo_ros_p3d.h.

event::ConnectionPtr gazebo::GazeboRosP3D::update_connection_
private

Definition at line 125 of file gazebo_ros_p3d.h.

double gazebo::GazeboRosP3D::update_rate_
private

Definition at line 109 of file gazebo_ros_p3d.h.

physics::WorldPtr gazebo::GazeboRosP3D::world_
private

Definition at line 62 of file gazebo_ros_p3d.h.


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


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27