#include <husky_plugin.h>
Public Member Functions | |
| HuskyPlugin () | |
| virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
| virtual void | UpdateChild () |
| virtual | ~HuskyPlugin () |
Private Member Functions | |
| void | OnCmdVel (const geometry_msgs::TwistConstPtr &msg) |
| void | OnContact (const std::string &name, const physics::Contact &contact) |
| void | spin () |
Private Attributes | |
| physics::CollisionPtr | base_geom_ |
| std::string | base_geom_name_ |
| std::string | bl_joint_name_ |
| std::string | br_joint_name_ |
| ros::Subscriber | cmd_vel_sub_ |
| std::string | fl_joint_name_ |
| std::string | fr_joint_name_ |
| ros::Publisher | joint_state_pub_ |
| physics::JointPtr | joints_ [4] |
| sensor_msgs::JointState | js_ |
| bool | kill_sim |
| common::Time | last_cmd_vel_time_ |
| physics::ModelPtr | model_ |
| std::string | node_namespace_ |
| Parameters. | |
| float | odom_pose_ [3] |
| ros::Publisher | odom_pub_ |
| float | odom_vel_ [3] |
| sensors::SensorPtr | parent_sensor_ |
| common::Time | prev_update_time_ |
| ros::NodeHandle * | rosnode_ |
| ros::Publisher | sensor_state_pub_ |
| bool | set_joints_ [4] |
| boost::thread * | spinner_thread_ |
| float | torque_ |
| Torque applied to the wheels. | |
| tf::TransformBroadcaster | transform_broadcaster_ |
| event::ConnectionPtr | updateConnection |
| float | wheel_diam_ |
| Diameter of the wheels. | |
| float | wheel_sep_ |
| Separation between the wheels. | |
| float * | wheel_speed_ |
| Speeds of the wheels. | |
| physics::WorldPtr | world_ |
Definition at line 28 of file husky_plugin.h.
Definition at line 49 of file husky_plugin.cpp.
| HuskyPlugin::~HuskyPlugin | ( | ) | [virtual] |
Definition at line 70 of file husky_plugin.cpp.
| void HuskyPlugin::Load | ( | physics::ModelPtr | _parent, |
| sdf::ElementPtr | _sdf | ||
| ) | [virtual] |
Definition at line 82 of file husky_plugin.cpp.
| void HuskyPlugin::OnCmdVel | ( | const geometry_msgs::TwistConstPtr & | msg | ) | [private] |
Definition at line 349 of file husky_plugin.cpp.
| void gazebo::HuskyPlugin::OnContact | ( | const std::string & | name, |
| const physics::Contact & | contact | ||
| ) | [private] |
| void HuskyPlugin::spin | ( | ) | [private] |
Definition at line 362 of file husky_plugin.cpp.
| void HuskyPlugin::UpdateChild | ( | ) | [virtual] |
Definition at line 193 of file husky_plugin.cpp.
physics::CollisionPtr gazebo::HuskyPlugin::base_geom_ [private] |
Definition at line 85 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::base_geom_name_ [private] |
Definition at line 50 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::bl_joint_name_ [private] |
Definition at line 46 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::br_joint_name_ [private] |
Definition at line 47 of file husky_plugin.h.
Definition at line 67 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::fl_joint_name_ [private] |
Definition at line 48 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::fr_joint_name_ [private] |
Definition at line 49 of file husky_plugin.h.
Definition at line 65 of file husky_plugin.h.
physics::JointPtr gazebo::HuskyPlugin::joints_[4] [private] |
Definition at line 84 of file husky_plugin.h.
sensor_msgs::JointState gazebo::HuskyPlugin::js_ [private] |
Definition at line 88 of file husky_plugin.h.
bool gazebo::HuskyPlugin::kill_sim [private] |
Definition at line 96 of file husky_plugin.h.
common::Time gazebo::HuskyPlugin::last_cmd_vel_time_ [private] |
Definition at line 78 of file husky_plugin.h.
physics::ModelPtr gazebo::HuskyPlugin::model_ [private] |
Definition at line 70 of file husky_plugin.h.
std::string gazebo::HuskyPlugin::node_namespace_ [private] |
Parameters.
Definition at line 45 of file husky_plugin.h.
float gazebo::HuskyPlugin::odom_pose_[3] [private] |
Definition at line 80 of file husky_plugin.h.
ros::Publisher gazebo::HuskyPlugin::odom_pub_ [private] |
Definition at line 64 of file husky_plugin.h.
float gazebo::HuskyPlugin::odom_vel_[3] [private] |
Definition at line 81 of file husky_plugin.h.
sensors::SensorPtr gazebo::HuskyPlugin::parent_sensor_ [private] |
Definition at line 71 of file husky_plugin.h.
common::Time gazebo::HuskyPlugin::prev_update_time_ [private] |
Definition at line 77 of file husky_plugin.h.
ros::NodeHandle* gazebo::HuskyPlugin::rosnode_ [private] |
Definition at line 61 of file husky_plugin.h.
Definition at line 63 of file husky_plugin.h.
bool gazebo::HuskyPlugin::set_joints_[4] [private] |
Definition at line 83 of file husky_plugin.h.
boost::thread* gazebo::HuskyPlugin::spinner_thread_ [private] |
Definition at line 91 of file husky_plugin.h.
float gazebo::HuskyPlugin::torque_ [private] |
Torque applied to the wheels.
Definition at line 59 of file husky_plugin.h.
Definition at line 87 of file husky_plugin.h.
Definition at line 94 of file husky_plugin.h.
float gazebo::HuskyPlugin::wheel_diam_ [private] |
Diameter of the wheels.
Definition at line 56 of file husky_plugin.h.
float gazebo::HuskyPlugin::wheel_sep_ [private] |
Separation between the wheels.
Definition at line 53 of file husky_plugin.h.
float* gazebo::HuskyPlugin::wheel_speed_ [private] |
Speeds of the wheels.
Definition at line 74 of file husky_plugin.h.
physics::WorldPtr gazebo::HuskyPlugin::world_ [private] |
Definition at line 69 of file husky_plugin.h.