38 #ifndef FORWARD_COMMAND_CONTROLLER_FORWARD_COMMAND_CONTROLLER_H 39 #define FORWARD_COMMAND_CONTROLLER_FORWARD_COMMAND_CONTROLLER_H 44 #include <std_msgs/Float64.h> 77 std::string joint_name;
78 if (!n.
getParam(
"joint", joint_name))
83 joint_ = hw->getHandle(joint_name);
void commandCB(const std_msgs::Float64ConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ForwardCommandController()
hardware_interface::JointHandle joint_
realtime_tools::RealtimeBuffer< double > command_buffer_
ros::Subscriber sub_command_
void starting(const ros::Time &time)
const std::string & getNamespace() const
~ForwardCommandController()
void update(const ros::Time &, const ros::Duration &)
void setCommand(double command)
bool getParam(const std::string &key, std::string &s) const
bool init(T *hw, ros::NodeHandle &n)