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 class ControllerToCSV
51 {
52 public:
57  ControllerToCSV(const std::string& topic);
58 
61 
63  bool recordAll();
64 
66  void startRecording(const std::string& file_name);
67 
69  void stopRecording();
70 
71 private:
73  bool writeToFile();
74 
76  void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr& state);
77 
79  void update(const ros::TimerEvent& e);
80 
82  bool waitForSubscriber(const ros::Subscriber& sub, const double& wait_time = 10.0);
83 
84  // Class name
85  std::string name_ = "controller_to_csv";
86 
87  // A shared node handle
89 
90  // Show status info on first update
91  bool first_update_;
92  bool recording_started_;
93 
94  // Listener to state of controller
96  double record_hz_; // how often to record the latest incoming data. if zero, record all
97 
98  // Where to save the CSV
99  std::string file_name_;
100 
101  // Buffer of controller state data
102  std::vector<control_msgs::JointTrajectoryControllerState> states_;
103  std::vector<ros::Time> timestamps_;
104 
105  // Cache of last recieved state
106  control_msgs::JointTrajectoryControllerState current_state_;
107 
108  // How often to sample the state
110 
111 }; // end class
112 
113 // Create std pointers for this class
114 typedef std::shared_ptr<ControllerToCSV> ControllerToCSVPtr;
115 typedef std::shared_ptr<const ControllerToCSV> ControllerToCSVConstPtr;
116 
117 } // namespace ros_control_boilerplate
118 
119 #endif
ros_control_boilerplate::ControllerToCSV::record_hz_
double record_hz_
Definition: controller_to_csv.h:160
ros_control_boilerplate::ControllerToCSV::states_
std::vector< control_msgs::JointTrajectoryControllerState > states_
Definition: controller_to_csv.h:166
ros_control_boilerplate
Definition: generic_hw_control_loop.h:44
ros_control_boilerplate::ControllerToCSV::recordAll
bool recordAll()
Whether to record at a specific frequency, or record all incoming data.
Definition: controller_to_csv.cpp:115
ros.h
ros_control_boilerplate::ControllerToCSV::stopRecording
void stopRecording()
End recording.
Definition: controller_to_csv.cpp:183
ros_control_boilerplate::ControllerToCSV::first_update_
bool first_update_
Definition: controller_to_csv.h:155
ros_control_boilerplate::ControllerToCSV::name_
std::string name_
Definition: controller_to_csv.h:149
ros_control_boilerplate::ControllerToCSV::file_name_
std::string file_name_
Definition: controller_to_csv.h:163
ros_control_boilerplate::ControllerToCSV::ControllerToCSV
ControllerToCSV(const std::string &topic)
Constructor.
Definition: controller_to_csv.cpp:82
ros_control_boilerplate::ControllerToCSV::startRecording
void startRecording(const std::string &file_name)
Start the data collection.
Definition: controller_to_csv.cpp:138
ros_control_boilerplate::ControllerToCSV::nh_
ros::NodeHandle nh_
Definition: controller_to_csv.h:152
ros_control_boilerplate::ControllerToCSV::current_state_
control_msgs::JointTrajectoryControllerState current_state_
Definition: controller_to_csv.h:170
ros_control_boilerplate::ControllerToCSV::update
void update(const ros::TimerEvent &e)
Recieve data from controller via ROS message.
Definition: controller_to_csv.cpp:157
ros::TimerEvent
ros_control_boilerplate::ControllerToCSVConstPtr
std::shared_ptr< const ControllerToCSV > ControllerToCSVConstPtr
Definition: controller_to_csv.h:147
ros_control_boilerplate::ControllerToCSV::~ControllerToCSV
~ControllerToCSV()
Destructor.
Definition: controller_to_csv.cpp:110
ros_control_boilerplate::ControllerToCSV::recording_started_
bool recording_started_
Definition: controller_to_csv.h:156
ros_control_boilerplate::ControllerToCSV::non_realtime_loop_
ros::Timer non_realtime_loop_
Definition: controller_to_csv.h:173
ros_control_boilerplate::ControllerToCSV::writeToFile
bool writeToFile()
Send all resulting data to file.
Definition: controller_to_csv.cpp:189
ros_control_boilerplate::ControllerToCSV::stateCB
void stateCB(const control_msgs::JointTrajectoryControllerState::ConstPtr &state)
Callback from ROS message.
Definition: controller_to_csv.cpp:120
ros_control_boilerplate::ControllerToCSV::waitForSubscriber
bool waitForSubscriber(const ros::Subscriber &sub, const double &wait_time=10.0)
Check if topic has been connected to successfully.
Definition: controller_to_csv.cpp:239
ros_control_boilerplate::ControllerToCSV::state_sub_
ros::Subscriber state_sub_
Definition: controller_to_csv.h:159
ros_control_boilerplate::ControllerToCSVPtr
std::shared_ptr< ControllerToCSV > ControllerToCSVPtr
Definition: controller_to_csv.h:146
ros_control_boilerplate::ControllerToCSV::timestamps_
std::vector< ros::Time > timestamps_
Definition: controller_to_csv.h:167
ros::Timer
ros::NodeHandle
ros::Subscriber


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Wed Mar 2 2022 00:52:14