#include <gazebo_ros_p3d.h>
Public Member Functions | |
GazeboRosP3D () | |
Constructor. | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
Load the controller. | |
virtual | ~GazeboRosP3D () |
Destructor. | |
Protected Member Functions | |
virtual void | UpdateChild () |
Update the controller. | |
Private Member Functions | |
double | GaussianKernel (double mu, double sigma) |
Gaussian noise generator. | |
void | P3DConnect () |
void | P3DDisconnect () |
void | P3DQueueThread () |
Private Attributes | |
math::Vector3 | aeul_ |
math::Vector3 | apos_ |
boost::thread | callback_queue_thread_ |
math::Vector3 | frame_aeul_ |
math::Vector3 | frame_apos_ |
std::string | frame_name_ |
frame transform name, should match link name FIXME: extract link name directly? | |
double | gaussian_noise_ |
Gaussian noise. | |
math::Vector3 | last_frame_veul_ |
math::Vector3 | last_frame_vpos_ |
common::Time | last_time_ |
save last_time | |
math::Vector3 | last_veul_ |
math::Vector3 | last_vpos_ |
physics::LinkPtr | link_ |
The parent Model. | |
std::string | link_name_ |
store bodyname | |
boost::mutex | lock |
A mutex to lock access to fields that are used in message callbacks. | |
physics::ModelPtr | model_ |
math::Pose | offset_ |
allow specifying constant xyz and rpy offsets | |
int | p3d_connect_count_ |
Keep track of number of connctions. | |
ros::CallbackQueue | p3d_queue_ |
nav_msgs::Odometry | pose_msg_ |
ros message | |
ros::Publisher | pub_ |
physics::LinkPtr | reference_link_ |
The body of the frame to display pose, twist. | |
std::string | robot_namespace_ |
for setting ROS name space | |
ros::NodeHandle * | rosnode_ |
pointer to ros node | |
std::string | tf_frame_name_ |
std::string | topic_name_ |
topic name | |
event::ConnectionPtr | update_connection_ |
double | update_rate_ |
physics::WorldPtr | world_ |
Definition at line 47 of file gazebo_ros_p3d.h.
Constructor.
Definition at line 38 of file gazebo_ros_p3d.cpp.
gazebo::GazeboRosP3D::~GazeboRosP3D | ( | ) | [virtual] |
Destructor.
Definition at line 45 of file gazebo_ros_p3d.cpp.
double gazebo::GazeboRosP3D::GaussianKernel | ( | double | mu, |
double | sigma | ||
) | [private] |
Gaussian noise generator.
Definition at line 331 of file gazebo_ros_p3d.cpp.
void gazebo::GazeboRosP3D::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the controller.
if frameName specified is "world", "/map" or "map" report back inertial values in the gazebo world
Definition at line 58 of file gazebo_ros_p3d.cpp.
void gazebo::GazeboRosP3D::P3DConnect | ( | ) | [private] |
Definition at line 196 of file gazebo_ros_p3d.cpp.
void gazebo::GazeboRosP3D::P3DDisconnect | ( | ) | [private] |
Definition at line 202 of file gazebo_ros_p3d.cpp.
void gazebo::GazeboRosP3D::P3DQueueThread | ( | ) | [private] |
Definition at line 347 of file gazebo_ros_p3d.cpp.
void gazebo::GazeboRosP3D::UpdateChild | ( | ) | [protected, virtual] |
Update the controller.
Definition at line 209 of file gazebo_ros_p3d.cpp.
math::Vector3 gazebo::GazeboRosP3D::aeul_ [private] |
Definition at line 100 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::apos_ [private] |
Definition at line 99 of file gazebo_ros_p3d.h.
boost::thread gazebo::GazeboRosP3D::callback_queue_thread_ [private] |
Definition at line 125 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::frame_aeul_ [private] |
Definition at line 104 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::frame_apos_ [private] |
Definition at line 103 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 86 of file gazebo_ros_p3d.h.
double gazebo::GazeboRosP3D::gaussian_noise_ [private] |
Gaussian noise.
Definition at line 110 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::last_frame_veul_ [private] |
Definition at line 102 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::last_frame_vpos_ [private] |
Definition at line 101 of file gazebo_ros_p3d.h.
common::Time gazebo::GazeboRosP3D::last_time_ [private] |
save last_time
Definition at line 96 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::last_veul_ [private] |
Definition at line 98 of file gazebo_ros_p3d.h.
math::Vector3 gazebo::GazeboRosP3D::last_vpos_ [private] |
Definition at line 97 of file gazebo_ros_p3d.h.
physics::LinkPtr gazebo::GazeboRosP3D::link_ [private] |
The parent Model.
Definition at line 65 of file gazebo_ros_p3d.h.
std::string gazebo::GazeboRosP3D::link_name_ [private] |
store bodyname
Definition at line 79 of file gazebo_ros_p3d.h.
boost::mutex gazebo::GazeboRosP3D::lock [private] |
A mutex to lock access to fields that are used in message callbacks.
Definition at line 93 of file gazebo_ros_p3d.h.
physics::ModelPtr gazebo::GazeboRosP3D::model_ [private] |
Definition at line 62 of file gazebo_ros_p3d.h.
math::Pose gazebo::GazeboRosP3D::offset_ [private] |
allow specifying constant xyz and rpy offsets
Definition at line 90 of file gazebo_ros_p3d.h.
int gazebo::GazeboRosP3D::p3d_connect_count_ [private] |
Keep track of number of connctions.
Definition at line 119 of file gazebo_ros_p3d.h.
Definition at line 123 of file gazebo_ros_p3d.h.
nav_msgs::Odometry gazebo::GazeboRosP3D::pose_msg_ [private] |
ros message
Definition at line 76 of file gazebo_ros_p3d.h.
ros::Publisher gazebo::GazeboRosP3D::pub_ [private] |
Definition at line 73 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 68 of file gazebo_ros_p3d.h.
std::string gazebo::GazeboRosP3D::robot_namespace_ [private] |
for setting ROS name space
Definition at line 116 of file gazebo_ros_p3d.h.
ros::NodeHandle* gazebo::GazeboRosP3D::rosnode_ [private] |
pointer to ros node
Definition at line 72 of file gazebo_ros_p3d.h.
std::string gazebo::GazeboRosP3D::tf_frame_name_ [private] |
Definition at line 87 of file gazebo_ros_p3d.h.
std::string gazebo::GazeboRosP3D::topic_name_ [private] |
topic name
Definition at line 82 of file gazebo_ros_p3d.h.
Definition at line 128 of file gazebo_ros_p3d.h.
double gazebo::GazeboRosP3D::update_rate_ [private] |
Definition at line 107 of file gazebo_ros_p3d.h.
physics::WorldPtr gazebo::GazeboRosP3D::world_ [private] |
Definition at line 61 of file gazebo_ros_p3d.h.