LeicaStateMachine.h
Go to the documentation of this file.
1 
18 #pragma once
19 #ifndef _LEICA_STATE_MACHINE_H
20 #define _LEICA_STATE_MACHINE_H
21 
22 // #include <iostream>
23 #include <boost/statechart/event.hpp>
24 #include <boost/statechart/state_machine.hpp>
25 #include <boost/statechart/simple_state.hpp>
26 #include <boost/statechart/state.hpp>
27 #include <boost/statechart/transition.hpp>
28 #include <boost/statechart/custom_reaction.hpp>
29 
30 #include <Utils.h>
31 #include <std_msgs/Int16.h>
32 
33 typedef pcl::PointCloud<pcl::PointXYZ> PointCloudXYZ;
34 typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloudRGB;
35 
36 // Events
37 class ValidEvent : public boost::statechart::event<ValidEvent>
38 {
39 public:
40  PointCloudRGB::Ptr source_cloud_;
41  PointCloudRGB::Ptr target_cloud_;
42 
43  ValidEvent(PointCloudRGB::Ptr source_cloud)
44  : source_cloud_(source_cloud) {}
45 
46  ValidEvent(PointCloudRGB::Ptr source_cloud, PointCloudRGB::Ptr target_cloud)
47  : source_cloud_(source_cloud), target_cloud_(target_cloud){}
48 };
49 
50 class ValidFODEvent : public boost::statechart::event<ValidFODEvent>
51 {
52 public:
53  int n_fod_;
54  std::vector<PointCloudRGB::Ptr> fods_cloud_array_;
55 
56  ValidFODEvent(int n_fods, std::vector<PointCloudRGB::Ptr> fods_cloud_array)
57  : n_fod_(n_fods), fods_cloud_array_(fods_cloud_array){}
58 };
59 
60 class NoValidEvent : public boost::statechart::event<NoValidEvent> {};
61 class StartEvent : public boost::statechart::event<StartEvent> {};
62 class PublishEvent : public boost::statechart::event<PublishEvent> {};
63 class StopPublishEvent : public boost::statechart::event<StopPublishEvent> {};
64 
65 // States
66 class IdleState;
67 class FilterState;
68 class AlignState;
69 class GICPState;
70 class FODDetectionState;
71 class ErrorState;
72 class PublishState;
73 class CallbackState;
74 
75 // State Machine
76 class StateMachine : public boost::statechart::state_machine< StateMachine, IdleState >
77 {
78 public:
79 
80  StateMachine(PointCloudRGB::Ptr source_cloud, PointCloudRGB::Ptr target_cloud, ros::NodeHandle nh);
81 
82  PointCloudRGB::Ptr source_cloud_;
83  PointCloudRGB::Ptr target_cloud_;
84  PointCloudRGB::Ptr source_cloud_filtered_;
85  PointCloudRGB::Ptr target_cloud_filtered_;
86  Eigen::Matrix4f cloud_transform_;
87 
88  int n_fod_;
89  std::vector<PointCloudRGB::Ptr> fods_cloud_array_;
90 
96 
97  void updateCloud(const ValidEvent& cloud)
98  {
99  ROS_INFO("Updating source cloud");
100  pcl::copyPointCloud(*cloud.source_cloud_, *source_cloud_);
101  }
102 
103  void updateClouds(const ValidEvent& clouds)
104  {
105  ROS_INFO("Updating clouds");
106  pcl::copyPointCloud(*clouds.source_cloud_, *source_cloud_);
107  pcl::copyPointCloud(*clouds.target_cloud_, *target_cloud_);
108  }
109 
110  void storeFODInfo(const ValidFODEvent& fod_info)
111  {
112  ROS_INFO("Storing FODs info");
113  n_fod_ = fod_info.n_fod_;
114  fods_cloud_array_ = fod_info.fods_cloud_array_;
115  }
116 
117  PointCloudRGB::Ptr getTargetCloud()
118  {
119  return target_cloud_;
120  }
121  PointCloudRGB::Ptr getSourceCloud()
122  {
123  return source_cloud_;
124  }
125 
126  PointCloudRGB::Ptr getSourceCloudFiltered()
127  {
128  return source_cloud_filtered_;
129  }
130  PointCloudRGB::Ptr getTargetCloudFiltered()
131  {
132  return target_cloud_filtered_;
133  }
134 
135  void setSourceCloudFiltered(PointCloudRGB::Ptr cloud_ptr)
136  {
137  source_cloud_filtered_ = cloud_ptr;
138  }
139  void setTargetCloudFiltered(PointCloudRGB::Ptr cloud_ptr)
140  {
141  target_cloud_filtered_ = cloud_ptr;
142  }
143 
144  Eigen::Matrix4f getCloudTransform()
145  {
146  return cloud_transform_;
147  }
148 
149  void setCloudTransform(Eigen::Matrix4f tf)
150  {
151  cloud_transform_ = tf;
152  }
153 
154  int getNFODs()
155  {
156  return n_fod_;
157  }
158 
159  std::vector<PointCloudRGB::Ptr> getFODCloudArray()
160  {
161  return fods_cloud_array_;
162  }
163 };
164 
165 // States
166 class IdleState : public boost::statechart::simple_state< IdleState, StateMachine >
167 {
168 public:
170  { ROS_INFO("Into IdleState."); }
171 
172  typedef boost::statechart::custom_reaction<StartEvent> reactions;
173 
174  boost::statechart::result react(const StartEvent&)
175  {
176  ROS_INFO("Transit to FilterState");
177  return transit< FilterState >();
178  }
179 };
180 
181 class FilterState : public boost::statechart::state< FilterState, StateMachine >
182 {
183 public:
184  FilterState(my_context ctx);
185 
186  typedef boost::mpl::list<
187  boost::statechart::custom_reaction<ValidEvent>,
188  boost::statechart::custom_reaction<NoValidEvent>
190 
191  boost::statechart::result react(const NoValidEvent&)
192  {
193  ROS_ERROR("Transit to Error");
194  return transit< ErrorState >();
195  }
196 
197  boost::statechart::result react(const ValidEvent& clouds)
198  {
199  ROS_INFO("Transit to AlignState");
200  return transit< AlignState >(&StateMachine::updateClouds, clouds);
201  }
202 };
203 
204 class AlignState : public boost::statechart::state< AlignState, StateMachine >
205 {
206 public:
207  AlignState(my_context ctx);
208 
209  typedef boost::mpl::list<
210  boost::statechart::custom_reaction<ValidEvent>,
211  boost::statechart::custom_reaction<NoValidEvent>
213 
214  boost::statechart::result react(const NoValidEvent&)
215  {
216  ROS_ERROR("Transit to Error");
217  return transit< ErrorState >();
218  }
219 
220  boost::statechart::result react(const ValidEvent& cloud)
221  {
222  ROS_INFO("Transit to GICPState");
223  return transit< GICPState >(&StateMachine::updateCloud, cloud);
224  }
225 };
226 
227 class GICPState : public boost::statechart::state< GICPState, StateMachine >
228 {
229 public:
230  GICPState(my_context ctx);
231 
232  typedef boost::mpl::list<
233  boost::statechart::custom_reaction<ValidEvent>,
234  boost::statechart::custom_reaction<NoValidEvent>
236 
237  boost::statechart::result react(const NoValidEvent&)
238  {
239  ROS_ERROR("Transit to Error");
240  return transit< ErrorState >();
241  }
242 
243  boost::statechart::result react(const ValidEvent& cloud)
244  {
245  ROS_INFO("Transit to FODDetectionState");
246  return transit< FODDetectionState >(&StateMachine::updateCloud, cloud);
247  }
248 };
249 
250 class FODDetectionState : public boost::statechart::state< FODDetectionState, StateMachine >
251 {
252 public:
253  FODDetectionState(my_context ctx);
254 
255  typedef boost::mpl::list<
256  boost::statechart::custom_reaction<ValidFODEvent>,
257  boost::statechart::custom_reaction<NoValidEvent>
259 
260  boost::statechart::result react(const NoValidEvent&)
261  {
262  ROS_ERROR("Transit to Error");
263  return transit< ErrorState >();
264  }
265 
266  boost::statechart::result react(const ValidFODEvent& cloud)
267  {
268  ROS_INFO("Transit to PublishState");
269  return transit< PublishState >(&StateMachine::storeFODInfo, cloud);
270  }
271 };
272 
273 class ErrorState : public boost::statechart::simple_state< ErrorState, StateMachine >
274 {
275 public:
276  ErrorState() { ROS_INFO("Into ErrorState"); };
277 };
278 
279 class PublishState : public boost::statechart::state< PublishState, StateMachine >
280 {
281 public:
282  PublishState(my_context ctx);
283 
284  typedef boost::mpl::list<
285  boost::statechart::custom_reaction<PublishEvent>,
286  boost::statechart::custom_reaction<StopPublishEvent>
288 
289  boost::statechart::result react(const PublishEvent&)
290  {
291  ROS_INFO("Loop on publish");
292  return transit< PublishState >();
293  }
294 
295  boost::statechart::result react(const StopPublishEvent&)
296  {
297  ROS_INFO("Stop publish");
298  }
299 };
300 
301 #endif
PointCloudRGB::Ptr getTargetCloud()
pcl::PointCloud< pcl::PointXYZRGB > PointCloudRGB
boost::mpl::list< boost::statechart::custom_reaction< ValidEvent >, boost::statechart::custom_reaction< NoValidEvent > > reactions
boost::mpl::list< boost::statechart::custom_reaction< ValidFODEvent >, boost::statechart::custom_reaction< NoValidEvent > > reactions
std::vector< PointCloudRGB::Ptr > getFODCloudArray()
Eigen::Matrix4f getCloudTransform()
void updateCloud(const ValidEvent &cloud)
PointCloudRGB::Ptr source_cloud_
boost::statechart::result react(const NoValidEvent &)
ros::Publisher target_pub_
boost::statechart::result react(const ValidFODEvent &cloud)
ValidEvent(PointCloudRGB::Ptr source_cloud)
std::vector< PointCloudRGB::Ptr > fods_cloud_array_
boost::mpl::list< boost::statechart::custom_reaction< ValidEvent >, boost::statechart::custom_reaction< NoValidEvent > > reactions
PointCloudRGB::Ptr getTargetCloudFiltered()
ros::Publisher fods_pub_
ros::Publisher source_pub_
Eigen::Matrix4f cloud_transform_
void setCloudTransform(Eigen::Matrix4f tf)
PointCloudRGB::Ptr source_cloud_filtered_
void storeFODInfo(const ValidFODEvent &fod_info)
boost::statechart::result react(const ValidEvent &cloud)
boost::mpl::list< boost::statechart::custom_reaction< ValidEvent >, boost::statechart::custom_reaction< NoValidEvent > > reactions
ros::NodeHandle nh_
#define ROS_INFO(...)
boost::statechart::result react(const StartEvent &)
ValidEvent(PointCloudRGB::Ptr source_cloud, PointCloudRGB::Ptr target_cloud)
PointCloudRGB::Ptr getSourceCloudFiltered()
ValidFODEvent(int n_fods, std::vector< PointCloudRGB::Ptr > fods_cloud_array)
boost::statechart::result react(const NoValidEvent &)
boost::statechart::result react(const NoValidEvent &)
boost::statechart::result react(const ValidEvent &clouds)
PointCloudRGB::Ptr target_cloud_filtered_
void updateClouds(const ValidEvent &clouds)
boost::statechart::result react(const StopPublishEvent &)
boost::statechart::result react(const NoValidEvent &)
void setSourceCloudFiltered(PointCloudRGB::Ptr cloud_ptr)
boost::statechart::custom_reaction< StartEvent > reactions
void setTargetCloudFiltered(PointCloudRGB::Ptr cloud_ptr)
ros::Publisher n_fods_pub_
boost::mpl::list< boost::statechart::custom_reaction< PublishEvent >, boost::statechart::custom_reaction< StopPublishEvent > > reactions
boost::statechart::result react(const ValidEvent &cloud)
pcl::PointCloud< pcl::PointXYZ > PointCloudXYZ
PointCloudRGB::Ptr getSourceCloud()
PointCloudRGB::Ptr target_cloud_
#define ROS_ERROR(...)
std::vector< PointCloudRGB::Ptr > fods_cloud_array_
PointCloudRGB::Ptr source_cloud_
PointCloudRGB::Ptr target_cloud_
boost::statechart::result react(const PublishEvent &)


leica_point_cloud_processing
Author(s): Ines Lara Sicilia
autogenerated on Mon Feb 28 2022 22:40:47