Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
gazebo::GrizzlyPlugin Class Reference

#include <grizzly_plugin.h>

List of all members.

Public Member Functions

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

Protected Member Functions

virtual void FiniChild ()
virtual void UpdateChild ()

Private Member Functions

void OnContact (const std::string &name, const physics::Contact &contact)
void OnDrive (const grizzly_msgs::DriveConstPtr &msg)
void spin ()

Private Attributes

physics::CollisionPtr base_geom_
std::string base_geom_name_
event::ConnectionPtr contact_event_
ros::Subscriber drive_sub_
ros::Publisher encoder_pub_
std::string fa_joint_name_
std::string fl_joint_name_
std::string fr_joint_name_
ros::Publisher joint_state_pub_
physics::JointPtr joints_ [5]
sensor_msgs::JointState js_
common::Time last_cmd_vel_time_
physics::ModelPtr model_
std::string node_namespace_
 Parameters.
ros::Publisher odom_pub_
sensors::SensorPtr parent_sensor_
common::Time prev_update_time_
std::string rl_joint_name_
ros::NodeHandlerosnode_
std::string rr_joint_name_
bool set_joints_ [5]
boost::thread * spinner_thread_
float torque_
 Torque applied to the wheels.
tf::TransformBroadcaster transform_broadcaster_
event::ConnectionPtr updateConnection
grizzly_msgs::Drive wheel_ang_vel_
 Speeds of the wheels.
physics::WorldPtr world_

Detailed Description

Definition at line 52 of file grizzly_plugin.h.


Constructor & Destructor Documentation

Definition at line 44 of file grizzly_plugin.cpp.

Definition at line 48 of file grizzly_plugin.cpp.


Member Function Documentation

void GrizzlyPlugin::FiniChild ( ) [protected, virtual]

Definition at line 54 of file grizzly_plugin.cpp.

void GrizzlyPlugin::Load ( physics::ModelPtr  _parent,
sdf::ElementPtr  _sdf 
) [virtual]

Definition at line 60 of file grizzly_plugin.cpp.

void gazebo::GrizzlyPlugin::OnContact ( const std::string name,
const physics::Contact &  contact 
) [private]
void GrizzlyPlugin::OnDrive ( const grizzly_msgs::DriveConstPtr &  msg) [private]

Definition at line 243 of file grizzly_plugin.cpp.

void GrizzlyPlugin::spin ( ) [private]

Definition at line 249 of file grizzly_plugin.cpp.

void GrizzlyPlugin::UpdateChild ( ) [protected, virtual]

Definition at line 178 of file grizzly_plugin.cpp.


Member Data Documentation

physics::CollisionPtr gazebo::GrizzlyPlugin::base_geom_ [private]

Definition at line 99 of file grizzly_plugin.h.

Definition at line 74 of file grizzly_plugin.h.

Definition at line 106 of file grizzly_plugin.h.

Definition at line 84 of file grizzly_plugin.h.

Definition at line 81 of file grizzly_plugin.h.

Definition at line 73 of file grizzly_plugin.h.

Definition at line 71 of file grizzly_plugin.h.

Definition at line 72 of file grizzly_plugin.h.

Definition at line 83 of file grizzly_plugin.h.

physics::JointPtr gazebo::GrizzlyPlugin::joints_[5] [private]

Definition at line 98 of file grizzly_plugin.h.

sensor_msgs::JointState gazebo::GrizzlyPlugin::js_ [private]

Definition at line 102 of file grizzly_plugin.h.

Definition at line 95 of file grizzly_plugin.h.

physics::ModelPtr gazebo::GrizzlyPlugin::model_ [private]

Definition at line 87 of file grizzly_plugin.h.

Parameters.

Definition at line 68 of file grizzly_plugin.h.

Definition at line 82 of file grizzly_plugin.h.

sensors::SensorPtr gazebo::GrizzlyPlugin::parent_sensor_ [private]

Definition at line 88 of file grizzly_plugin.h.

Definition at line 94 of file grizzly_plugin.h.

Definition at line 69 of file grizzly_plugin.h.

Definition at line 79 of file grizzly_plugin.h.

Definition at line 70 of file grizzly_plugin.h.

Definition at line 97 of file grizzly_plugin.h.

boost::thread* gazebo::GrizzlyPlugin::spinner_thread_ [private]

Definition at line 105 of file grizzly_plugin.h.

Torque applied to the wheels.

Definition at line 77 of file grizzly_plugin.h.

Definition at line 101 of file grizzly_plugin.h.

Definition at line 109 of file grizzly_plugin.h.

grizzly_msgs::Drive gazebo::GrizzlyPlugin::wheel_ang_vel_ [private]

Speeds of the wheels.

Definition at line 91 of file grizzly_plugin.h.

physics::WorldPtr gazebo::GrizzlyPlugin::world_ [private]

Definition at line 86 of file grizzly_plugin.h.


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


grizzly_gazebo_plugins
Author(s):
autogenerated on Thu Jun 6 2019 18:18:34