calibration.hpp
Go to the documentation of this file.
1 
8 #ifndef MARTY_CALIBRATION_HPP
9 #define MARTY_CALIBRATION_HPP
10 
11 // System
12 #include <iostream>
13 #include <fstream>
14 #include <unistd.h>
15 #include <termios.h>
16 #include <algorithm>
17 
18 // ROS
19 #include <ros/ros.h>
20 #include <ros/package.h>
21 
22 // Messages
23 #include <std_msgs/Bool.h>
24 #include <marty_msgs/ServoMsg.h>
25 #include <marty_msgs/ServoMsgArray.h>
26 
27 // MARTY
29 
30 class Calibration {
31  protected:
32  ros::NodeHandle nh_;
33  // NodeHandle instance must be created before this line.
34  // Otherwise strange error may occur.
35 
36  void loadParams();
37  void init();
38  void rosSetup();
39 
40  public:
41  Calibration(ros::NodeHandle& nh);
42  ~Calibration();
43  void calibrate();
44 
45  private:
46  void writeCalVals();
47  char getch();
48 
49 // Flags
50  bool enabled_;
51  bool saving_;
52  bool exiting_;
54  char c_;
55 
56 // Parameters
57 
58 // Variables
59  marty_msgs::ServoMsgArray joints_;
60  marty_msgs::ServoMsgArray cal_vals_;
61 
62 // ROS
63  ros::Publisher joint_pub_;
64  ros::Publisher enable_pub_;
65 
66 };
67 
68 #endif /* MARTY_CALIBRATION_HPP */
void loadParams()
Definition: calibration.cpp:23
ros::NodeHandle nh_
Definition: calibration.hpp:32
ros::Publisher joint_pub_
Definition: calibration.hpp:63
void rosSetup()
Definition: calibration.cpp:48
marty_msgs::ServoMsgArray joints_
Definition: calibration.hpp:59
marty_msgs::ServoMsgArray cal_vals_
Definition: calibration.hpp:60
ros::Publisher enable_pub_
Definition: calibration.hpp:64
void calibrate()
Definition: calibration.cpp:53
bool calibrated_
Definition: calibration.hpp:53
void writeCalVals()
Calibration(ros::NodeHandle &nh)
Definition: calibration.cpp:12


ros_marty
Author(s): Alejandro Bordallo
autogenerated on Fri Jul 21 2017 14:51:45