KinectMappingState.h
Go to the documentation of this file.
1 #ifndef MAPPINGSTATE_H
2 #define MAPPINGSTATE_H
3 
5 #include <rsm_core/BaseState.h>
6 #include <rsm_core/IdleState.h>
10 #include <rsm_msgs/GoalCompleted.h>
11 #include <sensor_msgs/JointState.h>
12 #include <std_msgs/Float64.h>
13 #include <std_srvs/Trigger.h>
14 
15 #define MOVE_LEFT 0
16 #define MOVE_RIGHT 1
17 #define MOVE_TO_CENTER 2
18 
19 #define KINECT_LEFT_LIMIT 1.30
20 #define KINECT_RIGHT_LIMIT -1.30
21 #define KINECT_CENTER_POSITION 0.0
22 
23 #define POS_TOLERANCE 0.05
24 
25 namespace rsm {
26 
33 
34 public:
35 
40 
45 
49  void onSetup();
50 
54  void onEntry();
55 
59  void onActive();
60 
64  void onExit();
65 
69  void onExplorationStart(bool &success, std::string &message);
70 
74  void onExplorationStop(bool &success, std::string &message);
75 
79  void onWaypointFollowingStart(bool &success, std::string &message);
80 
84  void onWaypointFollowingStop(bool &success, std::string &message);
85 
90  void onInterrupt(int interrupt);
91 
92 private:
93 
99 
116 
121  void jointStateCallback(sensor_msgs::JointState::ConstPtr joint_state);
122 };
123 
124 }
125 
126 #endif
Dummy state for mapping at a reached goal during exploration. Only initiates transition to CalculateG...
ros::ServiceClient _reset_kinect_position_client
ros::Publisher _kinect_joint_controller
ros::ServiceClient _navigation_goal_completed_service
void onWaypointFollowingStart(bool &success, std::string &message)
ros::Subscriber _joint_states_subscriber
void onExplorationStop(bool &success, std::string &message)
void onInterrupt(int interrupt)
Called when an operation mode interrupt was received.
void onExplorationStart(bool &success, std::string &message)
void onWaypointFollowingStop(bool &success, std::string &message)
void jointStateCallback(sensor_msgs::JointState::ConstPtr joint_state)


rsm_additions
Author(s): Marco Steinbrink
autogenerated on Tue Mar 16 2021 02:44:35