#include <gazebo_ros_p3d.h>
Definition at line 48 of file gazebo_ros_p3d.h.
◆ GazeboRosP3D()
gazebo::GazeboRosP3D::GazeboRosP3D |
( |
| ) |
|
◆ ~GazeboRosP3D()
gazebo::GazeboRosP3D::~GazeboRosP3D |
( |
| ) |
|
|
virtual |
◆ GaussianKernel()
double gazebo::GazeboRosP3D::GaussianKernel |
( |
double |
mu, |
|
|
double |
sigma |
|
) |
| |
|
private |
◆ Load()
void gazebo::GazeboRosP3D::Load |
( |
physics::ModelPtr |
_parent, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
◆ P3DQueueThread()
void gazebo::GazeboRosP3D::P3DQueueThread |
( |
| ) |
|
|
private |
◆ UpdateChild()
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.
◆ aeul_
ignition::math::Vector3d gazebo::GazeboRosP3D::aeul_ |
|
private |
◆ apos_
ignition::math::Vector3d gazebo::GazeboRosP3D::apos_ |
|
private |
◆ callback_queue_thread_
boost::thread gazebo::GazeboRosP3D::callback_queue_thread_ |
|
private |
◆ frame_aeul_
ignition::math::Vector3d gazebo::GazeboRosP3D::frame_aeul_ |
|
private |
◆ frame_apos_
ignition::math::Vector3d gazebo::GazeboRosP3D::frame_apos_ |
|
private |
◆ frame_name_
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.
◆ gaussian_noise_
double gazebo::GazeboRosP3D::gaussian_noise_ |
|
private |
◆ last_frame_veul_
ignition::math::Vector3d gazebo::GazeboRosP3D::last_frame_veul_ |
|
private |
◆ last_frame_vpos_
ignition::math::Vector3d gazebo::GazeboRosP3D::last_frame_vpos_ |
|
private |
◆ last_time_
common::Time gazebo::GazeboRosP3D::last_time_ |
|
private |
◆ last_veul_
ignition::math::Vector3d gazebo::GazeboRosP3D::last_veul_ |
|
private |
◆ last_vpos_
ignition::math::Vector3d gazebo::GazeboRosP3D::last_vpos_ |
|
private |
◆ link_
physics::LinkPtr gazebo::GazeboRosP3D::link_ |
|
private |
◆ link_name_
std::string gazebo::GazeboRosP3D::link_name_ |
|
private |
◆ lock
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.
◆ model_
physics::ModelPtr gazebo::GazeboRosP3D::model_ |
|
private |
◆ offset_
ignition::math::Pose3d gazebo::GazeboRosP3D::offset_ |
|
private |
allow specifying constant xyz and rpy offsets
Definition at line 92 of file gazebo_ros_p3d.h.
◆ p3d_queue_
◆ pmq
◆ pose_msg_
nav_msgs::Odometry gazebo::GazeboRosP3D::pose_msg_ |
|
private |
◆ pub_
◆ pub_Queue
PubQueue<nav_msgs::Odometry>::Ptr gazebo::GazeboRosP3D::pub_Queue |
|
private |
◆ reference_link_
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.
◆ robot_namespace_
std::string gazebo::GazeboRosP3D::robot_namespace_ |
|
private |
◆ rosnode_
◆ tf_frame_name_
std::string gazebo::GazeboRosP3D::tf_frame_name_ |
|
private |
◆ topic_name_
std::string gazebo::GazeboRosP3D::topic_name_ |
|
private |
◆ update_connection_
◆ update_rate_
double gazebo::GazeboRosP3D::update_rate_ |
|
private |
◆ world_
physics::WorldPtr gazebo::GazeboRosP3D::world_ |
|
private |
The documentation for this class was generated from the following files: