32 #include <std_msgs/Float64.h> 33 #include <std_srvs/Empty.h> 36 #include <controller_manager/controller_manager.h> 48 template <
unsigned int NUM_JOINTS = 2>
58 std::fill_n(
pos_, NUM_JOINTS, 0.0);
59 std::fill_n(
vel_, NUM_JOINTS, 0.0);
60 std::fill_n(
eff_, NUM_JOINTS, 0.0);
61 std::fill_n(
cmd_, NUM_JOINTS, 0.0);
64 for (
unsigned int i = 0; i < NUM_JOINTS; ++i)
66 std::ostringstream os;
67 os <<
"wheel_" << i <<
"_joint";
85 std::ostringstream os;
86 for (
unsigned int i = 0; i < NUM_JOINTS - 1; ++i)
88 os <<
cmd_[i] <<
", ";
90 os <<
cmd_[NUM_JOINTS - 1];
99 for (
unsigned int i = 0; i < NUM_JOINTS; ++i)
110 std::fill_n(
pos_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
111 std::fill_n(
vel_, NUM_JOINTS, std::numeric_limits<double>::quiet_NaN());
void registerInterface(T *iface)
hardware_interface::JointStateInterface jnt_state_interface_
bool start_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::ServiceServer stop_srv_
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)
ros::Time getTime() const
hardware_interface::VelocityJointInterface jnt_vel_interface_
ros::ServiceServer start_srv_
void registerHandle(const JointStateHandle &handle)
JointStateHandle getHandle(const std::string &name)
#define ROS_INFO_STREAM(args)
bool stop_callback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)