$search
#include <gazebo_ros_kurt.h>
Public Member Functions | |
| virtual void | FiniChild () |
| GazeboRosKurt (gazebo::Entity *parent) | |
| virtual void | InitChild () |
| virtual void | LoadChild (XMLConfigNode *node) |
| virtual void | UpdateChild () |
| virtual | ~GazeboRosKurt () |
Private Member Functions | |
| void | OnCmdVel (const geometry_msgs::TwistConstPtr &msg) |
Private Attributes | |
| ros::Subscriber | cmd_vel_sub_ |
| std::string | cmd_vel_topic_name_ |
| ParamT< std::string > * | cmd_vel_topic_nameP_ |
| std::vector< ParamT < std::string > * > | joint_nameP_ |
| ros::Publisher | joint_state_pub_ |
| std::string | joint_states_topic_name_ |
| ParamT< std::string > * | joint_states_topic_nameP_ |
| Joint * | joints_ [NUM_JOINTS] |
| sensor_msgs::JointState | js_ |
| Time | last_cmd_vel_time_ |
| ParamT< float > * | max_velocityP_ |
| maximum forward speed of Kurt [m/s] | |
| Model * | my_parent_ |
| float | odom_pose_ [3] |
| ros::Publisher | odom_pub_ |
| std::string | odom_topic_name_ |
| ParamT< std::string > * | odom_topic_nameP_ |
| float | odom_vel_ [3] |
| Time | prev_update_time_ |
| ParamT< std::string > * | robotNamespaceP_ |
| ros::NodeHandle * | rosnode_ |
| ParamT< float > * | torqueP_ |
| maximum torque applied to the wheels [Nm] | |
| tf::TransformBroadcaster | transform_broadcaster_ |
| ParamT< float > * | turning_adaptationP_ |
| Turning adaptation for odometry. | |
| ParamT< float > * | wheel_diamP_ |
| Diameter of the wheels. | |
| ParamT< float > * | wheel_sepP_ |
| Separation between the wheels. | |
| float | wheel_speed_left_ |
| float | wheel_speed_right_ |
| Desired speeds of the wheels. | |
Static Private Attributes | |
| static const double | CMD_VEL_TIMEOUT = 0.6 |
| static const size_t | NUM_JOINTS = 6 |
Definition at line 17 of file gazebo_ros_kurt.h.
| gazebo::GazeboRosKurt::GazeboRosKurt | ( | gazebo::Entity * | parent | ) |
| GazeboRosKurt::~GazeboRosKurt | ( | ) | [virtual] |
Definition at line 57 of file gazebo_ros_kurt.cpp.
| void GazeboRosKurt::FiniChild | ( | ) | [virtual] |
Definition at line 127 of file gazebo_ros_kurt.cpp.
| void GazeboRosKurt::InitChild | ( | ) | [virtual] |
Definition at line 123 of file gazebo_ros_kurt.cpp.
| void GazeboRosKurt::LoadChild | ( | XMLConfigNode * | node | ) | [virtual] |
Definition at line 77 of file gazebo_ros_kurt.cpp.
| void GazeboRosKurt::OnCmdVel | ( | const geometry_msgs::TwistConstPtr & | msg | ) | [private] |
Definition at line 236 of file gazebo_ros_kurt.cpp.
| void GazeboRosKurt::UpdateChild | ( | ) | [virtual] |
Definition at line 132 of file gazebo_ros_kurt.cpp.
Definition at line 39 of file gazebo_ros_kurt.h.
const double gazebo::GazeboRosKurt::CMD_VEL_TIMEOUT = 0.6 [static, private] |
Definition at line 30 of file gazebo_ros_kurt.h.
std::string gazebo::GazeboRosKurt::cmd_vel_topic_name_ [private] |
Definition at line 44 of file gazebo_ros_kurt.h.
ParamT<std::string>* gazebo::GazeboRosKurt::cmd_vel_topic_nameP_ [private] |
Definition at line 43 of file gazebo_ros_kurt.h.
std::vector<ParamT<std::string> *> gazebo::GazeboRosKurt::joint_nameP_ [private] |
Definition at line 50 of file gazebo_ros_kurt.h.
Definition at line 37 of file gazebo_ros_kurt.h.
std::string gazebo::GazeboRosKurt::joint_states_topic_name_ [private] |
Definition at line 48 of file gazebo_ros_kurt.h.
ParamT<std::string>* gazebo::GazeboRosKurt::joint_states_topic_nameP_ [private] |
Definition at line 47 of file gazebo_ros_kurt.h.
Joint* gazebo::GazeboRosKurt::joints_[NUM_JOINTS] [private] |
Definition at line 73 of file gazebo_ros_kurt.h.
Definition at line 85 of file gazebo_ros_kurt.h.
Time gazebo::GazeboRosKurt::last_cmd_vel_time_ [private] |
Definition at line 79 of file gazebo_ros_kurt.h.
ParamT<float>* gazebo::GazeboRosKurt::max_velocityP_ [private] |
maximum forward speed of Kurt [m/s]
Definition at line 65 of file gazebo_ros_kurt.h.
Model* gazebo::GazeboRosKurt::my_parent_ [private] |
Definition at line 67 of file gazebo_ros_kurt.h.
const size_t gazebo::GazeboRosKurt::NUM_JOINTS = 6 [static, private] |
Definition at line 29 of file gazebo_ros_kurt.h.
float gazebo::GazeboRosKurt::odom_pose_[3] [private] |
Definition at line 81 of file gazebo_ros_kurt.h.
Definition at line 36 of file gazebo_ros_kurt.h.
std::string gazebo::GazeboRosKurt::odom_topic_name_ [private] |
Definition at line 46 of file gazebo_ros_kurt.h.
ParamT<std::string>* gazebo::GazeboRosKurt::odom_topic_nameP_ [private] |
Definition at line 45 of file gazebo_ros_kurt.h.
float gazebo::GazeboRosKurt::odom_vel_[3] [private] |
Definition at line 82 of file gazebo_ros_kurt.h.
Time gazebo::GazeboRosKurt::prev_update_time_ [private] |
Definition at line 76 of file gazebo_ros_kurt.h.
ParamT<std::string>* gazebo::GazeboRosKurt::robotNamespaceP_ [private] |
Definition at line 41 of file gazebo_ros_kurt.h.
ros::NodeHandle* gazebo::GazeboRosKurt::rosnode_ [private] |
Definition at line 34 of file gazebo_ros_kurt.h.
ParamT<float>* gazebo::GazeboRosKurt::torqueP_ [private] |
maximum torque applied to the wheels [Nm]
Definition at line 62 of file gazebo_ros_kurt.h.
Definition at line 84 of file gazebo_ros_kurt.h.
ParamT<float>* gazebo::GazeboRosKurt::turning_adaptationP_ [private] |
Turning adaptation for odometry.
Definition at line 59 of file gazebo_ros_kurt.h.
ParamT<float>* gazebo::GazeboRosKurt::wheel_diamP_ [private] |
Diameter of the wheels.
Definition at line 56 of file gazebo_ros_kurt.h.
ParamT<float>* gazebo::GazeboRosKurt::wheel_sepP_ [private] |
Separation between the wheels.
Definition at line 53 of file gazebo_ros_kurt.h.
float gazebo::GazeboRosKurt::wheel_speed_left_ [private] |
Definition at line 71 of file gazebo_ros_kurt.h.
float gazebo::GazeboRosKurt::wheel_speed_right_ [private] |
Desired speeds of the wheels.
Definition at line 70 of file gazebo_ros_kurt.h.