5 #include <std_msgs/Float64.h>     6 #include <std_srvs/Empty.h>     9 #include <controller_manager/controller_manager.h>    29     std::vector<std::string> velocity_joints_name = {
"front_left_wheel", 
"front_right_wheel",
    30                                                      "rear_left_wheel", 
"rear_right_wheel"};
    32     for (
unsigned int i = 0; i < velocity_joints_name.size(); ++i)
    42     std::vector<std::string> position_joints_name = {
"front_left_steering_joint", 
"front_right_steering_joint",
    43                                                      "rear_left_steering_joint", 
"rear_right_steering_joint"};
    45     for (
unsigned int i = 0; i < position_joints_name.size(); ++i)
    64     std::ostringstream os;
    65     for (
unsigned int i = 0; i < 3; ++i)
    74     for (
unsigned int i = 0; i < 3; ++i)
    86       for (
unsigned int i = 0; i < 4; ++i)
    94       for (
unsigned int i = 0; i < 4; ++i)
   101       for (
unsigned int i = 0; i < 4; ++i)
   106       for (
unsigned int i = 0; i < 4; ++i)
   138     Joint() : position(0), velocity(0), effort(0), velocity_command(0) { }
   148     SteeringJoint() : position(0), velocity(0), effort(0), position_command(0) { }
 void registerInterface(T *iface)
struct FourWheelSteering::Joint joints_[4]
ros::ServiceServer stop_srv_
ros::Time getTime() const 
ros::Duration getPeriod() const 
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
bool start_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool stop_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
struct FourWheelSteering::SteeringJoint steering_joints_[4]
#define ROS_DEBUG_STREAM(args)
hardware_interface::VelocityJointInterface jnt_vel_interface_
ros::ServiceServer start_srv_
void registerHandle(const JointStateHandle &handle)
hardware_interface::PositionJointInterface jnt_pos_interface_
hardware_interface::JointStateInterface jnt_state_interface_