39 #ifndef GENERIC_ROS_CONTROL__CONTROLLER_TO_CSV_H 40 #define GENERIC_ROS_CONTROL__CONTROLLER_TO_CSV_H 46 #include <control_msgs/JointTrajectoryControllerState.h> 78 void stateCB(
const control_msgs::JointTrajectoryControllerState::ConstPtr& state);
87 std::string
name_ =
"controller_to_csv";
104 std::vector<control_msgs::JointTrajectoryControllerState>
states_;
~ControllerToCSV()
Destructor.
void stopRecording()
End recording.
bool writeToFile()
Send all resulting data to file.
void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr &state)
Callback from ROS message.
void update(const ros::TimerEvent &e)
Recieve data from controller via ROS message.
bool recordAll()
Whether to record at a specific frequency, or record all incoming data.
control_msgs::JointTrajectoryControllerState current_state_
ros::Subscriber state_sub_
boost::shared_ptr< ControllerToCSV > ControllerToCSVPtr
boost::shared_ptr< const ControllerToCSV > ControllerToCSVConstPtr
std::vector< ros::Time > timestamps_
ros::Timer non_realtime_loop_
std::vector< control_msgs::JointTrajectoryControllerState > states_
bool waitForSubscriber(const ros::Subscriber &sub, const double &wait_time=10.0)
Check if topic has been connected to successfully.
void startRecording(const std::string &file_name)
Start the data collection.
ControllerToCSV(const std::string &topic)
Constructor.