controller_to_csv.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman
36  Desc: Records a ros_control ControllerState data to CSV for Matlab/etc analysis
37 */
38 
39 #ifndef GENERIC_ROS_CONTROL__CONTROLLER_TO_CSV_H
40 #define GENERIC_ROS_CONTROL__CONTROLLER_TO_CSV_H
41 
42 // ROS
43 #include <ros/ros.h>
44 
45 // ros_control
46 #include <control_msgs/JointTrajectoryControllerState.h>
47 
49 {
50 
52 {
53 public:
58  ControllerToCSV(const std::string& topic);
59 
62 
64  bool recordAll();
65 
67  void startRecording(const std::string& file_name);
68 
70  void stopRecording();
71 
72 private:
73 
75  bool writeToFile();
76 
78  void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr& state);
79 
81  void update(const ros::TimerEvent& e);
82 
84  bool waitForSubscriber(const ros::Subscriber &sub, const double &wait_time = 10.0);
85 
86  // Class name
87  std::string name_ = "controller_to_csv";
88 
89  // A shared node handle
91 
92  // Show status info on first update
95 
96  // Listener to state of controller
98  double record_hz_; // how often to record the latest incoming data. if zero, record all
99 
100  // Where to save the CSV
101  std::string file_name_;
102 
103  // Buffer of controller state data
104  std::vector<control_msgs::JointTrajectoryControllerState> states_;
105  std::vector<ros::Time> timestamps_;
106 
107  // Cache of last recieved state
108  control_msgs::JointTrajectoryControllerState current_state_;
109 
110  // How often to sample the state
112 
113 }; // end class
114 
115 // Create boost pointers for this class
118 
119 } // end namespace
120 
121 #endif
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_
boost::shared_ptr< ControllerToCSV > ControllerToCSVPtr
boost::shared_ptr< const ControllerToCSV > ControllerToCSVConstPtr
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.


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Thu Feb 25 2021 03:58:54