Go to the documentation of this file.
47 #include <std_msgs/Float64MultiArray.h>
81 std::string param_name =
"joints";
117 {
joints_[i].setCommand(commands[i]); }
121 std::vector< hardware_interface::JointHandle >
joints_;
127 void commandCB(
const std_msgs::Float64MultiArrayConstPtr& msg)
131 ROS_ERROR_STREAM(
"Dimension of command (" << msg->data.size() <<
") does not match number of joints (" <<
n_joints_ <<
")! Not executing!");
#define ROS_ERROR_STREAM(args)
const char * what() const noexcept override
bool getParam(const std::string &key, bool &b) const
void commandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
std::vector< hardware_interface::JointHandle > joints_
ros::Subscriber sub_command_
void starting(const ros::Time &time)
std::vector< std::string > joint_names_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
bool init(T *hw, ros::NodeHandle &n)
ForwardJointGroupCommandController()
void update(const ros::Time &, const ros::Duration &)
const std::string & getNamespace() const
~ForwardJointGroupCommandController()
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_