37 #include <std_msgs/Float64.h> 38 #include <std_srvs/Empty.h> 41 #include <controller_manager/controller_manager.h> 65 ,
ns_(
"ackermann_steering_bot_hw_sim/")
84 std::ostringstream os;
145 os << front_steer_jnt_pos_ <<
", ";
158 std::ostringstream os;
182 if (rear_wheel_jnt_vel_cmd_ != 0.0 || front_steer_jnt_pos_cmd_ != 0.0)
195 bool stopCallback(std_srvs::Empty::Request& , std_srvs::Empty::Response& )
337 const std::string _jnt_name,
double& _jnt_pos,
double& _jnt_vel,
double& _jnt_eff,
double& _jnt_cmd)
341 _jnt_pos, _jnt_vel, _jnt_eff);
343 _jnt_name, _jnt_cmd);
348 const std::string _jnt_name,
double& _jnt_pos,
double& _jnt_vel,
double& _jnt_eff)
356 ROS_INFO_STREAM(
"Registered joint '" << _jnt_name <<
" ' in the JointStateInterface");
362 const std::string _jnt_name,
double& _jnt_cmd)
369 ROS_INFO_STREAM(
"Registered joint '" << _jnt_name <<
" ' in the CommandJointInterface");
void registerInterface(T *iface)
std::vector< double > virtual_rear_wheel_jnt_eff_
double rear_wheel_jnt_eff_
std::vector< double > virtual_front_wheel_jnt_vel_cmd_
hardware_interface::JointStateInterface jnt_state_interface_
std::string rear_wheel_jnt_name_
void registerWheelInterface()
void getSteerJointNames(ros::NodeHandle &_nh)
void registerCommandJointInterfaceHandle(hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_cmd)
bool stopCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::vector< double > virtual_rear_wheel_jnt_pos_
std::vector< double > virtual_front_steer_jnt_pos_cmd_
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)
hardware_interface::VelocityJointInterface rear_wheel_jnt_vel_cmd_interface_
std::string front_steer_jnt_name_
std::vector< double > virtual_front_steer_jnt_vel_
void registerSteerInterface()
void registerInterfaceHandles(hardware_interface::JointStateInterface &_jnt_state_interface, hardware_interface::JointCommandInterface &_jnt_cmd_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff, double &_jnt_cmd)
hardware_interface::PositionJointInterface front_steer_jnt_pos_cmd_interface_
double rear_wheel_jnt_pos_
double rear_wheel_jnt_vel_cmd_
void registerJointStateInterfaceHandle(hardware_interface::JointStateInterface &_jnt_state_interface, const std::string _jnt_name, double &_jnt_pos, double &_jnt_vel, double &_jnt_eff)
double wheel_separation_w_
void registerHardwareInterfaces()
std::vector< double > virtual_front_steer_jnt_pos_
void getJointNames(ros::NodeHandle &_nh)
double front_steer_jnt_vel_
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer stop_srv_
std::vector< double > virtual_rear_wheel_jnt_vel_cmd_
std::vector< double > virtual_front_steer_jnt_eff_
std::vector< double > virtual_front_wheel_jnt_eff_
std::vector< double > virtual_rear_wheel_jnt_vel_
void registerHandle(const JointStateHandle &handle)
double rear_wheel_jnt_vel_
double front_steer_jnt_pos_
JointStateHandle getHandle(const std::string &name)
void getWheelJointNames(ros::NodeHandle &_nh)
std::vector< std::string > virtual_front_steer_jnt_names_
#define ROS_INFO_STREAM(args)
std::vector< double > virtual_front_wheel_jnt_vel_
bool startCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::Duration getPeriod() const
double front_steer_jnt_pos_cmd_
std::vector< std::string > virtual_front_wheel_jnt_names_
std::vector< double > virtual_front_wheel_jnt_pos_
ros::Time getTime() const
std::vector< std::string > virtual_rear_wheel_jnt_names_
ros::ServiceServer start_srv_
double wheel_separation_h_
double front_steer_jnt_eff_