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

#include <gazebo_ros_create.h>

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

Public Member Functions

 GazeboRosCreate ()
 
virtual void Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf)
 
virtual void UpdateChild ()
 
virtual ~GazeboRosCreate ()
 

Private Member Functions

void OnCmdVel (const geometry_msgs::TwistConstPtr &msg)
 
void OnContact (ConstContactsPtr &contact)
 
void spin ()
 
void UpdateSensors ()
 

Private Attributes

physics::CollisionPtr base_geom_
 
std::string base_geom_name_
 
ros::Subscriber cmd_vel_sub_
 
transport::SubscriberPtr contact_sub_
 
std::string front_castor_joint_name_
 
transport::NodePtr gazebo_node_
 
ros::Publisher joint_state_pub_
 
physics::JointPtr joints_ [4]
 
sensor_msgs::JointState js_
 
common::Time last_cmd_vel_time_
 
sensors::RaySensorPtr left_cliff_sensor_
 
std::string left_wheel_joint_name_
 
sensors::RaySensorPtr leftfront_cliff_sensor_
 
physics::ModelPtr my_parent_
 
physics::WorldPtr my_world_
 
std::string node_namespace_
 Parameters. More...
 
float odom_pose_ [3]
 
ros::Publisher odom_pub_
 
float odom_vel_ [3]
 
common::Time prev_update_time_
 
std::string rear_castor_joint_name_
 
sensors::RaySensorPtr right_cliff_sensor_
 
std::string right_wheel_joint_name_
 
sensors::RaySensorPtr rightfront_cliff_sensor_
 
ros::NodeHandlerosnode_
 
create_node::TurtlebotSensorState sensor_state_
 
ros::Publisher sensor_state_pub_
 
bool set_joints_ [4]
 
boost::thread * spinner_thread_
 
float torque_
 Torque applied to the wheels. More...
 
tf::TransformBroadcaster transform_broadcaster_
 
event::ConnectionPtr updateConnection
 
sensors::RaySensorPtr wall_sensor_
 
float wheel_diam_
 Diameter of the wheels. More...
 
float wheel_sep_
 Separation between the wheels. More...
 
float * wheel_speed_
 Speeds of the wheels. More...
 

Detailed Description

Definition at line 22 of file gazebo_ros_create.h.

Constructor & Destructor Documentation

GazeboRosCreate::GazeboRosCreate ( )

Definition at line 13 of file gazebo_ros_create.cpp.

GazeboRosCreate::~GazeboRosCreate ( )
virtual

Definition at line 32 of file gazebo_ros_create.cpp.

Member Function Documentation

void GazeboRosCreate::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 41 of file gazebo_ros_create.cpp.

void GazeboRosCreate::OnCmdVel ( const geometry_msgs::TwistConstPtr &  msg)
private

Definition at line 400 of file gazebo_ros_create.cpp.

void GazeboRosCreate::OnContact ( ConstContactsPtr &  contact)
private

Definition at line 206 of file gazebo_ros_create.cpp.

void GazeboRosCreate::spin ( )
private

Definition at line 411 of file gazebo_ros_create.cpp.

void GazeboRosCreate::UpdateChild ( )
virtual

Definition at line 232 of file gazebo_ros_create.cpp.

void GazeboRosCreate::UpdateSensors ( )
private

Definition at line 367 of file gazebo_ros_create.cpp.

Member Data Documentation

physics::CollisionPtr gazebo::GazeboRosCreate::base_geom_
private

Definition at line 82 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::base_geom_name_
private

Definition at line 45 of file gazebo_ros_create.h.

ros::Subscriber gazebo::GazeboRosCreate::cmd_vel_sub_
private

Definition at line 65 of file gazebo_ros_create.h.

transport::SubscriberPtr gazebo::GazeboRosCreate::contact_sub_
private

Definition at line 100 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::front_castor_joint_name_
private

Definition at line 43 of file gazebo_ros_create.h.

transport::NodePtr gazebo::GazeboRosCreate::gazebo_node_
private

Definition at line 99 of file gazebo_ros_create.h.

ros::Publisher gazebo::GazeboRosCreate::joint_state_pub_
private

Definition at line 63 of file gazebo_ros_create.h.

physics::JointPtr gazebo::GazeboRosCreate::joints_[4]
private

Definition at line 81 of file gazebo_ros_create.h.

sensor_msgs::JointState gazebo::GazeboRosCreate::js_
private

Definition at line 91 of file gazebo_ros_create.h.

common::Time gazebo::GazeboRosCreate::last_cmd_vel_time_
private

Definition at line 75 of file gazebo_ros_create.h.

sensors::RaySensorPtr gazebo::GazeboRosCreate::left_cliff_sensor_
private

Definition at line 84 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::left_wheel_joint_name_
private

Definition at line 41 of file gazebo_ros_create.h.

sensors::RaySensorPtr gazebo::GazeboRosCreate::leftfront_cliff_sensor_
private

Definition at line 85 of file gazebo_ros_create.h.

physics::ModelPtr gazebo::GazeboRosCreate::my_parent_
private

Definition at line 68 of file gazebo_ros_create.h.

physics::WorldPtr gazebo::GazeboRosCreate::my_world_
private

Definition at line 67 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::node_namespace_
private

Parameters.

Definition at line 40 of file gazebo_ros_create.h.

float gazebo::GazeboRosCreate::odom_pose_[3]
private

Definition at line 77 of file gazebo_ros_create.h.

ros::Publisher gazebo::GazeboRosCreate::odom_pub_
private

Definition at line 62 of file gazebo_ros_create.h.

float gazebo::GazeboRosCreate::odom_vel_[3]
private

Definition at line 78 of file gazebo_ros_create.h.

common::Time gazebo::GazeboRosCreate::prev_update_time_
private

Definition at line 74 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::rear_castor_joint_name_
private

Definition at line 44 of file gazebo_ros_create.h.

sensors::RaySensorPtr gazebo::GazeboRosCreate::right_cliff_sensor_
private

Definition at line 87 of file gazebo_ros_create.h.

std::string gazebo::GazeboRosCreate::right_wheel_joint_name_
private

Definition at line 42 of file gazebo_ros_create.h.

sensors::RaySensorPtr gazebo::GazeboRosCreate::rightfront_cliff_sensor_
private

Definition at line 86 of file gazebo_ros_create.h.

ros::NodeHandle* gazebo::GazeboRosCreate::rosnode_
private

Definition at line 57 of file gazebo_ros_create.h.

create_node::TurtlebotSensorState gazebo::GazeboRosCreate::sensor_state_
private

Definition at line 93 of file gazebo_ros_create.h.

ros::Publisher gazebo::GazeboRosCreate::sensor_state_pub_
private

Definition at line 61 of file gazebo_ros_create.h.

bool gazebo::GazeboRosCreate::set_joints_[4]
private

Definition at line 80 of file gazebo_ros_create.h.

boost::thread* gazebo::GazeboRosCreate::spinner_thread_
private

Definition at line 96 of file gazebo_ros_create.h.

float gazebo::GazeboRosCreate::torque_
private

Torque applied to the wheels.

Definition at line 54 of file gazebo_ros_create.h.

tf::TransformBroadcaster gazebo::GazeboRosCreate::transform_broadcaster_
private

Definition at line 90 of file gazebo_ros_create.h.

event::ConnectionPtr gazebo::GazeboRosCreate::updateConnection
private

Definition at line 103 of file gazebo_ros_create.h.

sensors::RaySensorPtr gazebo::GazeboRosCreate::wall_sensor_
private

Definition at line 88 of file gazebo_ros_create.h.

float gazebo::GazeboRosCreate::wheel_diam_
private

Diameter of the wheels.

Definition at line 51 of file gazebo_ros_create.h.

float gazebo::GazeboRosCreate::wheel_sep_
private

Separation between the wheels.

Definition at line 48 of file gazebo_ros_create.h.

float* gazebo::GazeboRosCreate::wheel_speed_
private

Speeds of the wheels.

Definition at line 71 of file gazebo_ros_create.h.


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


create_gazebo_plugins
Author(s): Nate Koenig
autogenerated on Mon Jun 10 2019 15:38:07