39 #ifndef GENERIC_ROS_CONTROL__CSV_TO_CONTROLLER_H 40 #define GENERIC_ROS_CONTROL__CSV_TO_CONTROLLER_H 46 #include <control_msgs/FollowJointTrajectoryAction.h> 47 #include <control_msgs/JointTrajectoryControllerState.h> 64 const std::string& controller_state_topic);
67 void stateCB(
const control_msgs::JointTrajectoryControllerState::ConstPtr& state);
69 void printPoint(trajectory_msgs::JointTrajectoryPoint &point);
void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr &state)
Callback from ROS message.
std::string controller_state_topic_
control_msgs::JointTrajectoryControllerState current_state_
CSVToController(const std::string &joint_trajectory_action, const std::string &controller_state_topic)
Constructor.
static const double RECORD_RATE_HZ
void printPoint(trajectory_msgs::JointTrajectoryPoint &point)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > joint_trajectory_action_
ros::Subscriber state_sub_
void loadAndRunCSV(const std::string &file_name)