common_state_callbacks.h
Go to the documentation of this file.
00001 
00030 #ifndef BEBOP_AUTONOMY_AUTOGENERATED_common_STATE_CALLBACKS_H
00031 #define BEBOP_AUTONOMY_AUTOGENERATED_common_STATE_CALLBACKS_H
00032 
00033 extern "C"
00034 {
00035   #include "libARSAL/ARSAL.h"
00036   #include "libARController/ARController.h"
00037 }
00038 
00039 #include "bebop_driver/autogenerated/callbacks_common.h"
00040 #include "bebop_driver/BebopArdrone3Config.h"
00041 
00042 #include "bebop_msgs/CommonCommonStateAllStatesChanged.h"
00043 #include "bebop_msgs/CommonCommonStateBatteryStateChanged.h"
00044 #include "bebop_msgs/CommonCommonStateMassStorageStateListChanged.h"
00045 #include "bebop_msgs/CommonCommonStateMassStorageInfoStateListChanged.h"
00046 #include "bebop_msgs/CommonCommonStateCurrentDateChanged.h"
00047 #include "bebop_msgs/CommonCommonStateCurrentTimeChanged.h"
00048 #include "bebop_msgs/CommonCommonStateMassStorageInfoRemainingListChanged.h"
00049 #include "bebop_msgs/CommonCommonStateWifiSignalChanged.h"
00050 #include "bebop_msgs/CommonCommonStateSensorsStatesListChanged.h"
00051 #include "bebop_msgs/CommonCommonStateProductModel.h"
00052 #include "bebop_msgs/CommonCommonStateCountryListKnown.h"
00053 #include "bebop_msgs/CommonCommonStateDeprecatedMassStorageContentChanged.h"
00054 #include "bebop_msgs/CommonCommonStateMassStorageContent.h"
00055 #include "bebop_msgs/CommonCommonStateMassStorageContentForCurrentRun.h"
00056 #include "bebop_msgs/CommonCommonStateVideoRecordingTimestamp.h"
00057 #include "bebop_msgs/CommonOverHeatStateOverHeatChanged.h"
00058 #include "bebop_msgs/CommonOverHeatStateOverHeatRegulationChanged.h"
00059 #include "bebop_msgs/CommonMavlinkStateMavlinkFilePlayingStateChanged.h"
00060 #include "bebop_msgs/CommonMavlinkStateMavlinkPlayErrorStateChanged.h"
00061 #include "bebop_msgs/CommonMavlinkStateMissionItemExecuted.h"
00062 #include "bebop_msgs/CommonCalibrationStateMagnetoCalibrationStateChanged.h"
00063 #include "bebop_msgs/CommonCalibrationStateMagnetoCalibrationRequiredState.h"
00064 #include "bebop_msgs/CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged.h"
00065 #include "bebop_msgs/CommonCalibrationStateMagnetoCalibrationStartedChanged.h"
00066 #include "bebop_msgs/CommonCalibrationStatePitotCalibrationStateChanged.h"
00067 #include "bebop_msgs/CommonFlightPlanStateAvailabilityStateChanged.h"
00068 #include "bebop_msgs/CommonFlightPlanStateComponentStateListChanged.h"
00069 #include "bebop_msgs/CommonFlightPlanStateLockStateChanged.h"
00070 #include "bebop_msgs/CommonARLibsVersionsStateControllerLibARCommandsVersion.h"
00071 #include "bebop_msgs/CommonARLibsVersionsStateSkyControllerLibARCommandsVersion.h"
00072 #include "bebop_msgs/CommonARLibsVersionsStateDeviceLibARCommandsVersion.h"
00073 #include "bebop_msgs/CommonAudioStateAudioStreamingRunning.h"
00074 #include "bebop_msgs/CommonHeadlightsStateintensityChanged.h"
00075 #include "bebop_msgs/CommonAnimationsStateList.h"
00076 #include "bebop_msgs/CommonAccessoryStateSupportedAccessoriesListChanged.h"
00077 #include "bebop_msgs/CommonAccessoryStateAccessoryConfigChanged.h"
00078 #include "bebop_msgs/CommonAccessoryStateAccessoryConfigModificationEnabled.h"
00079 #include "bebop_msgs/CommonChargerStateMaxChargeRateChanged.h"
00080 #include "bebop_msgs/CommonChargerStateCurrentChargeStateChanged.h"
00081 #include "bebop_msgs/CommonChargerStateLastChargeRateChanged.h"
00082 #include "bebop_msgs/CommonChargerStateChargingInfo.h"
00083 #include "bebop_msgs/CommonRunStateRunIdChanged.h"
00084 
00085 namespace bebop_driver
00086 {
00087 namespace cb
00088 {
00089 
00090 
00091 // All states have been sent.\n\n **Please note that you should not care about this event if you are using the libARController API as this library is handling the connection process for you.**
00092 class CommonCommonStateAllStatesChanged : public AbstractState
00093 {
00094 private:
00095   ::bebop_msgs::CommonCommonStateAllStatesChanged::Ptr msg_ptr;
00096 
00097 public:
00098 
00099   CommonCommonStateAllStatesChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00100     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_ALLSTATESCHANGED)
00101   {
00102     if (priv_nh.getParam("states/enable_commonstate_allstateschanged", pub_enabled_) && pub_enabled_)
00103     {
00104       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00105       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateAllStatesChanged>(topic, 10, true);
00106     } // pub_enabled_ is false
00107   }
00108 
00109   ::bebop_msgs::CommonCommonStateAllStatesChanged::ConstPtr GetDataCstPtr() const
00110   {
00111     ::boost::lock_guard<boost::mutex> lock(mutex_);
00112     return msg_ptr;
00113   }
00114 
00115   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00116   {
00117     if (arguments == NULL)
00118     {
00119       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateAllStatesChanged::Update() arguments is NULL");
00120       return;
00121     }
00122 
00123     ::boost::lock_guard<boost::mutex> lock(mutex_);
00124     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateAllStatesChanged());
00125     msg_ptr->header.stamp = t;
00126     msg_ptr->header.frame_id = "base_link";
00127 
00128 
00129     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00130   }
00131 
00132 };  // CommonCommonStateAllStatesChanged
00133 
00134 
00135 // Battery state.
00136 class CommonCommonStateBatteryStateChanged : public AbstractState
00137 {
00138 private:
00139   ::bebop_msgs::CommonCommonStateBatteryStateChanged::Ptr msg_ptr;
00140 
00141 public:
00142 
00143   CommonCommonStateBatteryStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00144     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_BATTERYSTATECHANGED)
00145   {
00146     if (priv_nh.getParam("states/enable_commonstate_batterystatechanged", pub_enabled_) && pub_enabled_)
00147     {
00148       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00149       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateBatteryStateChanged>(topic, 10, true);
00150     } // pub_enabled_ is false
00151   }
00152 
00153   ::bebop_msgs::CommonCommonStateBatteryStateChanged::ConstPtr GetDataCstPtr() const
00154   {
00155     ::boost::lock_guard<boost::mutex> lock(mutex_);
00156     return msg_ptr;
00157   }
00158 
00159   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00160   {
00161     if (arguments == NULL)
00162     {
00163       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateBatteryStateChanged::Update() arguments is NULL");
00164       return;
00165     }
00166 
00167     ::boost::lock_guard<boost::mutex> lock(mutex_);
00168     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateBatteryStateChanged());
00169     msg_ptr->header.stamp = t;
00170     msg_ptr->header.frame_id = "base_link";
00171 
00172 
00173     arg = NULL;
00174     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_BATTERYSTATECHANGED_PERCENT, arg);
00175     if (arg)
00176     {
00177       msg_ptr->percent = arg->value.U8;
00178     }
00179 
00180     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00181   }
00182 
00183 };  // CommonCommonStateBatteryStateChanged
00184 
00185 
00186 // Mass storage state list.
00187 class CommonCommonStateMassStorageStateListChanged : public AbstractState
00188 {
00189 private:
00190   ::bebop_msgs::CommonCommonStateMassStorageStateListChanged::Ptr msg_ptr;
00191 
00192 public:
00193 
00194   CommonCommonStateMassStorageStateListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00195     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGESTATELISTCHANGED)
00196   {
00197     if (priv_nh.getParam("states/enable_commonstate_massstoragestatelistchanged", pub_enabled_) && pub_enabled_)
00198     {
00199       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00200       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateMassStorageStateListChanged>(topic, 10, true);
00201     } // pub_enabled_ is false
00202   }
00203 
00204   ::bebop_msgs::CommonCommonStateMassStorageStateListChanged::ConstPtr GetDataCstPtr() const
00205   {
00206     ::boost::lock_guard<boost::mutex> lock(mutex_);
00207     return msg_ptr;
00208   }
00209 
00210   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00211   {
00212     if (arguments == NULL)
00213     {
00214       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateMassStorageStateListChanged::Update() arguments is NULL");
00215       return;
00216     }
00217 
00218     ::boost::lock_guard<boost::mutex> lock(mutex_);
00219     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateMassStorageStateListChanged());
00220     msg_ptr->header.stamp = t;
00221     msg_ptr->header.frame_id = "base_link";
00222 
00223 
00224     arg = NULL;
00225     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGESTATELISTCHANGED_MASS_STORAGE_ID, arg);
00226     if (arg)
00227     {
00228       msg_ptr->mass_storage_id = arg->value.U8;
00229     }
00230 
00231     arg = NULL;
00232     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGESTATELISTCHANGED_NAME, arg);
00233     if (arg)
00234     {
00235       msg_ptr->name = arg->value.String;
00236     }
00237 
00238     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00239   }
00240 
00241 };  // CommonCommonStateMassStorageStateListChanged
00242 
00243 
00244 // Mass storage info state list.
00245 class CommonCommonStateMassStorageInfoStateListChanged : public AbstractState
00246 {
00247 private:
00248   ::bebop_msgs::CommonCommonStateMassStorageInfoStateListChanged::Ptr msg_ptr;
00249 
00250 public:
00251 
00252   CommonCommonStateMassStorageInfoStateListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00253     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED)
00254   {
00255     if (priv_nh.getParam("states/enable_commonstate_massstorageinfostatelistchanged", pub_enabled_) && pub_enabled_)
00256     {
00257       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00258       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateMassStorageInfoStateListChanged>(topic, 10, true);
00259     } // pub_enabled_ is false
00260   }
00261 
00262   ::bebop_msgs::CommonCommonStateMassStorageInfoStateListChanged::ConstPtr GetDataCstPtr() const
00263   {
00264     ::boost::lock_guard<boost::mutex> lock(mutex_);
00265     return msg_ptr;
00266   }
00267 
00268   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00269   {
00270     if (arguments == NULL)
00271     {
00272       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateMassStorageInfoStateListChanged::Update() arguments is NULL");
00273       return;
00274     }
00275 
00276     ::boost::lock_guard<boost::mutex> lock(mutex_);
00277     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateMassStorageInfoStateListChanged());
00278     msg_ptr->header.stamp = t;
00279     msg_ptr->header.frame_id = "base_link";
00280 
00281 
00282     arg = NULL;
00283     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_MASS_STORAGE_ID, arg);
00284     if (arg)
00285     {
00286       msg_ptr->mass_storage_id = arg->value.U8;
00287     }
00288 
00289     arg = NULL;
00290     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_SIZE, arg);
00291     if (arg)
00292     {
00293       msg_ptr->size = arg->value.U32;
00294     }
00295 
00296     arg = NULL;
00297     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_USED_SIZE, arg);
00298     if (arg)
00299     {
00300       msg_ptr->used_size = arg->value.U32;
00301     }
00302 
00303     arg = NULL;
00304     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_PLUGGED, arg);
00305     if (arg)
00306     {
00307       msg_ptr->plugged = arg->value.U8;
00308     }
00309 
00310     arg = NULL;
00311     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_FULL, arg);
00312     if (arg)
00313     {
00314       msg_ptr->full = arg->value.U8;
00315     }
00316 
00317     arg = NULL;
00318     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOSTATELISTCHANGED_INTERNAL, arg);
00319     if (arg)
00320     {
00321       msg_ptr->internal = arg->value.U8;
00322     }
00323 
00324     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00325   }
00326 
00327 };  // CommonCommonStateMassStorageInfoStateListChanged
00328 
00329 
00330 // Date changed.\n Corresponds to the latest date set on the drone.\n\n **Please note that you should not care about this event if you are using the libARController API as this library is handling the connection process for you.**
00331 class CommonCommonStateCurrentDateChanged : public AbstractState
00332 {
00333 private:
00334   ::bebop_msgs::CommonCommonStateCurrentDateChanged::Ptr msg_ptr;
00335 
00336 public:
00337 
00338   CommonCommonStateCurrentDateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00339     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_CURRENTDATECHANGED)
00340   {
00341     if (priv_nh.getParam("states/enable_commonstate_currentdatechanged", pub_enabled_) && pub_enabled_)
00342     {
00343       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00344       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateCurrentDateChanged>(topic, 10, true);
00345     } // pub_enabled_ is false
00346   }
00347 
00348   ::bebop_msgs::CommonCommonStateCurrentDateChanged::ConstPtr GetDataCstPtr() const
00349   {
00350     ::boost::lock_guard<boost::mutex> lock(mutex_);
00351     return msg_ptr;
00352   }
00353 
00354   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00355   {
00356     if (arguments == NULL)
00357     {
00358       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateCurrentDateChanged::Update() arguments is NULL");
00359       return;
00360     }
00361 
00362     ::boost::lock_guard<boost::mutex> lock(mutex_);
00363     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateCurrentDateChanged());
00364     msg_ptr->header.stamp = t;
00365     msg_ptr->header.frame_id = "base_link";
00366 
00367 
00368     arg = NULL;
00369     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_CURRENTDATECHANGED_DATE, arg);
00370     if (arg)
00371     {
00372       msg_ptr->date = arg->value.String;
00373     }
00374 
00375     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00376   }
00377 
00378 };  // CommonCommonStateCurrentDateChanged
00379 
00380 
00381 // Time changed.\n Corresponds to the latest time set on the drone.\n\n **Please note that you should not care about this event if you are using the libARController API as this library is handling the connection process for you.**
00382 class CommonCommonStateCurrentTimeChanged : public AbstractState
00383 {
00384 private:
00385   ::bebop_msgs::CommonCommonStateCurrentTimeChanged::Ptr msg_ptr;
00386 
00387 public:
00388 
00389   CommonCommonStateCurrentTimeChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00390     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_CURRENTTIMECHANGED)
00391   {
00392     if (priv_nh.getParam("states/enable_commonstate_currenttimechanged", pub_enabled_) && pub_enabled_)
00393     {
00394       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00395       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateCurrentTimeChanged>(topic, 10, true);
00396     } // pub_enabled_ is false
00397   }
00398 
00399   ::bebop_msgs::CommonCommonStateCurrentTimeChanged::ConstPtr GetDataCstPtr() const
00400   {
00401     ::boost::lock_guard<boost::mutex> lock(mutex_);
00402     return msg_ptr;
00403   }
00404 
00405   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00406   {
00407     if (arguments == NULL)
00408     {
00409       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateCurrentTimeChanged::Update() arguments is NULL");
00410       return;
00411     }
00412 
00413     ::boost::lock_guard<boost::mutex> lock(mutex_);
00414     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateCurrentTimeChanged());
00415     msg_ptr->header.stamp = t;
00416     msg_ptr->header.frame_id = "base_link";
00417 
00418 
00419     arg = NULL;
00420     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_CURRENTTIMECHANGED_TIME, arg);
00421     if (arg)
00422     {
00423       msg_ptr->time = arg->value.String;
00424     }
00425 
00426     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00427   }
00428 
00429 };  // CommonCommonStateCurrentTimeChanged
00430 
00431 
00432 // Mass storage remaining data list.
00433 class CommonCommonStateMassStorageInfoRemainingListChanged : public AbstractState
00434 {
00435 private:
00436   ::bebop_msgs::CommonCommonStateMassStorageInfoRemainingListChanged::Ptr msg_ptr;
00437 
00438 public:
00439 
00440   CommonCommonStateMassStorageInfoRemainingListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00441     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOREMAININGLISTCHANGED)
00442   {
00443     if (priv_nh.getParam("states/enable_commonstate_massstorageinforemaininglistchanged", pub_enabled_) && pub_enabled_)
00444     {
00445       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00446       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateMassStorageInfoRemainingListChanged>(topic, 10, true);
00447     } // pub_enabled_ is false
00448   }
00449 
00450   ::bebop_msgs::CommonCommonStateMassStorageInfoRemainingListChanged::ConstPtr GetDataCstPtr() const
00451   {
00452     ::boost::lock_guard<boost::mutex> lock(mutex_);
00453     return msg_ptr;
00454   }
00455 
00456   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00457   {
00458     if (arguments == NULL)
00459     {
00460       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateMassStorageInfoRemainingListChanged::Update() arguments is NULL");
00461       return;
00462     }
00463 
00464     ::boost::lock_guard<boost::mutex> lock(mutex_);
00465     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateMassStorageInfoRemainingListChanged());
00466     msg_ptr->header.stamp = t;
00467     msg_ptr->header.frame_id = "base_link";
00468 
00469 
00470     arg = NULL;
00471     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOREMAININGLISTCHANGED_FREE_SPACE, arg);
00472     if (arg)
00473     {
00474       msg_ptr->free_space = arg->value.U32;
00475     }
00476 
00477     arg = NULL;
00478     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOREMAININGLISTCHANGED_REC_TIME, arg);
00479     if (arg)
00480     {
00481       msg_ptr->rec_time = arg->value.U16;
00482     }
00483 
00484     arg = NULL;
00485     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGEINFOREMAININGLISTCHANGED_PHOTO_REMAINING, arg);
00486     if (arg)
00487     {
00488       msg_ptr->photo_remaining = arg->value.U32;
00489     }
00490 
00491     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00492   }
00493 
00494 };  // CommonCommonStateMassStorageInfoRemainingListChanged
00495 
00496 
00497 // Rssi (Wifi Signal between controller and product) changed.
00498 class CommonCommonStateWifiSignalChanged : public AbstractState
00499 {
00500 private:
00501   ::bebop_msgs::CommonCommonStateWifiSignalChanged::Ptr msg_ptr;
00502 
00503 public:
00504 
00505   CommonCommonStateWifiSignalChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00506     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_WIFISIGNALCHANGED)
00507   {
00508     if (priv_nh.getParam("states/enable_commonstate_wifisignalchanged", pub_enabled_) && pub_enabled_)
00509     {
00510       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00511       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateWifiSignalChanged>(topic, 10, true);
00512     } // pub_enabled_ is false
00513   }
00514 
00515   ::bebop_msgs::CommonCommonStateWifiSignalChanged::ConstPtr GetDataCstPtr() const
00516   {
00517     ::boost::lock_guard<boost::mutex> lock(mutex_);
00518     return msg_ptr;
00519   }
00520 
00521   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00522   {
00523     if (arguments == NULL)
00524     {
00525       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateWifiSignalChanged::Update() arguments is NULL");
00526       return;
00527     }
00528 
00529     ::boost::lock_guard<boost::mutex> lock(mutex_);
00530     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateWifiSignalChanged());
00531     msg_ptr->header.stamp = t;
00532     msg_ptr->header.frame_id = "base_link";
00533 
00534 
00535     arg = NULL;
00536     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_WIFISIGNALCHANGED_RSSI, arg);
00537     if (arg)
00538     {
00539       msg_ptr->rssi = arg->value.I16;
00540     }
00541 
00542     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00543   }
00544 
00545 };  // CommonCommonStateWifiSignalChanged
00546 
00547 
00548 // Sensors state list.
00549 class CommonCommonStateSensorsStatesListChanged : public AbstractState
00550 {
00551 private:
00552   ::bebop_msgs::CommonCommonStateSensorsStatesListChanged::Ptr msg_ptr;
00553 
00554 public:
00555 
00556   CommonCommonStateSensorsStatesListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00557     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_SENSORSSTATESLISTCHANGED)
00558   {
00559     if (priv_nh.getParam("states/enable_commonstate_sensorsstateslistchanged", pub_enabled_) && pub_enabled_)
00560     {
00561       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00562       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateSensorsStatesListChanged>(topic, 10, true);
00563     } // pub_enabled_ is false
00564   }
00565 
00566   ::bebop_msgs::CommonCommonStateSensorsStatesListChanged::ConstPtr GetDataCstPtr() const
00567   {
00568     ::boost::lock_guard<boost::mutex> lock(mutex_);
00569     return msg_ptr;
00570   }
00571 
00572   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00573   {
00574     if (arguments == NULL)
00575     {
00576       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateSensorsStatesListChanged::Update() arguments is NULL");
00577       return;
00578     }
00579 
00580     ::boost::lock_guard<boost::mutex> lock(mutex_);
00581     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateSensorsStatesListChanged());
00582     msg_ptr->header.stamp = t;
00583     msg_ptr->header.frame_id = "base_link";
00584 
00585 
00586     arg = NULL;
00587     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_SENSORSSTATESLISTCHANGED_SENSORNAME, arg);
00588     if (arg)
00589     {
00590       msg_ptr->sensorName = arg->value.I32;
00591     }
00592 
00593     arg = NULL;
00594     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_SENSORSSTATESLISTCHANGED_SENSORSTATE, arg);
00595     if (arg)
00596     {
00597       msg_ptr->sensorState = arg->value.U8;
00598     }
00599 
00600     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00601   }
00602 
00603 };  // CommonCommonStateSensorsStatesListChanged
00604 
00605 
00606 // Product sub-model.\n This can be used to customize the UI depending on the product.
00607 class CommonCommonStateProductModel : public AbstractState
00608 {
00609 private:
00610   ::bebop_msgs::CommonCommonStateProductModel::Ptr msg_ptr;
00611 
00612 public:
00613 
00614   CommonCommonStateProductModel(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00615     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_PRODUCTMODEL)
00616   {
00617     if (priv_nh.getParam("states/enable_commonstate_productmodel", pub_enabled_) && pub_enabled_)
00618     {
00619       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00620       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateProductModel>(topic, 10, true);
00621     } // pub_enabled_ is false
00622   }
00623 
00624   ::bebop_msgs::CommonCommonStateProductModel::ConstPtr GetDataCstPtr() const
00625   {
00626     ::boost::lock_guard<boost::mutex> lock(mutex_);
00627     return msg_ptr;
00628   }
00629 
00630   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00631   {
00632     if (arguments == NULL)
00633     {
00634       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateProductModel::Update() arguments is NULL");
00635       return;
00636     }
00637 
00638     ::boost::lock_guard<boost::mutex> lock(mutex_);
00639     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateProductModel());
00640     msg_ptr->header.stamp = t;
00641     msg_ptr->header.frame_id = "base_link";
00642 
00643 
00644     arg = NULL;
00645     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_PRODUCTMODEL_MODEL, arg);
00646     if (arg)
00647     {
00648       msg_ptr->model = arg->value.I32;
00649     }
00650 
00651     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00652   }
00653 
00654 };  // CommonCommonStateProductModel
00655 
00656 
00657 // List of countries known by the drone.
00658 class CommonCommonStateCountryListKnown : public AbstractState
00659 {
00660 private:
00661   ::bebop_msgs::CommonCommonStateCountryListKnown::Ptr msg_ptr;
00662 
00663 public:
00664 
00665   CommonCommonStateCountryListKnown(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00666     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_COUNTRYLISTKNOWN)
00667   {
00668     if (priv_nh.getParam("states/enable_commonstate_countrylistknown", pub_enabled_) && pub_enabled_)
00669     {
00670       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00671       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateCountryListKnown>(topic, 10, true);
00672     } // pub_enabled_ is false
00673   }
00674 
00675   ::bebop_msgs::CommonCommonStateCountryListKnown::ConstPtr GetDataCstPtr() const
00676   {
00677     ::boost::lock_guard<boost::mutex> lock(mutex_);
00678     return msg_ptr;
00679   }
00680 
00681   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00682   {
00683     if (arguments == NULL)
00684     {
00685       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateCountryListKnown::Update() arguments is NULL");
00686       return;
00687     }
00688 
00689     ::boost::lock_guard<boost::mutex> lock(mutex_);
00690     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateCountryListKnown());
00691     msg_ptr->header.stamp = t;
00692     msg_ptr->header.frame_id = "base_link";
00693 
00694 
00695     arg = NULL;
00696     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_COUNTRYLISTKNOWN_LISTFLAGS, arg);
00697     if (arg)
00698     {
00699       msg_ptr->listFlags = arg->value.U8;
00700     }
00701 
00702     arg = NULL;
00703     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_COUNTRYLISTKNOWN_COUNTRYCODES, arg);
00704     if (arg)
00705     {
00706       msg_ptr->countryCodes = arg->value.String;
00707     }
00708 
00709     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00710   }
00711 
00712 };  // CommonCommonStateCountryListKnown
00713 
00714 
00715 // Mass storage content changed.
00716 class CommonCommonStateDeprecatedMassStorageContentChanged : public AbstractState
00717 {
00718 private:
00719   ::bebop_msgs::CommonCommonStateDeprecatedMassStorageContentChanged::Ptr msg_ptr;
00720 
00721 public:
00722 
00723   CommonCommonStateDeprecatedMassStorageContentChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00724     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED)
00725   {
00726     if (priv_nh.getParam("states/enable_commonstate_deprecatedmassstoragecontentchanged", pub_enabled_) && pub_enabled_)
00727     {
00728       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00729       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateDeprecatedMassStorageContentChanged>(topic, 10, true);
00730     } // pub_enabled_ is false
00731   }
00732 
00733   ::bebop_msgs::CommonCommonStateDeprecatedMassStorageContentChanged::ConstPtr GetDataCstPtr() const
00734   {
00735     ::boost::lock_guard<boost::mutex> lock(mutex_);
00736     return msg_ptr;
00737   }
00738 
00739   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00740   {
00741     if (arguments == NULL)
00742     {
00743       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateDeprecatedMassStorageContentChanged::Update() arguments is NULL");
00744       return;
00745     }
00746 
00747     ::boost::lock_guard<boost::mutex> lock(mutex_);
00748     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateDeprecatedMassStorageContentChanged());
00749     msg_ptr->header.stamp = t;
00750     msg_ptr->header.frame_id = "base_link";
00751 
00752 
00753     arg = NULL;
00754     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED_MASS_STORAGE_ID, arg);
00755     if (arg)
00756     {
00757       msg_ptr->mass_storage_id = arg->value.U8;
00758     }
00759 
00760     arg = NULL;
00761     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED_NBPHOTOS, arg);
00762     if (arg)
00763     {
00764       msg_ptr->nbPhotos = arg->value.U16;
00765     }
00766 
00767     arg = NULL;
00768     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED_NBVIDEOS, arg);
00769     if (arg)
00770     {
00771       msg_ptr->nbVideos = arg->value.U16;
00772     }
00773 
00774     arg = NULL;
00775     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED_NBPUDS, arg);
00776     if (arg)
00777     {
00778       msg_ptr->nbPuds = arg->value.U16;
00779     }
00780 
00781     arg = NULL;
00782     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_DEPRECATEDMASSSTORAGECONTENTCHANGED_NBCRASHLOGS, arg);
00783     if (arg)
00784     {
00785       msg_ptr->nbCrashLogs = arg->value.U16;
00786     }
00787 
00788     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00789   }
00790 
00791 };  // CommonCommonStateDeprecatedMassStorageContentChanged
00792 
00793 
00794 // Mass storage content.
00795 class CommonCommonStateMassStorageContent : public AbstractState
00796 {
00797 private:
00798   ::bebop_msgs::CommonCommonStateMassStorageContent::Ptr msg_ptr;
00799 
00800 public:
00801 
00802   CommonCommonStateMassStorageContent(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00803     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT)
00804   {
00805     if (priv_nh.getParam("states/enable_commonstate_massstoragecontent", pub_enabled_) && pub_enabled_)
00806     {
00807       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00808       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateMassStorageContent>(topic, 10, true);
00809     } // pub_enabled_ is false
00810   }
00811 
00812   ::bebop_msgs::CommonCommonStateMassStorageContent::ConstPtr GetDataCstPtr() const
00813   {
00814     ::boost::lock_guard<boost::mutex> lock(mutex_);
00815     return msg_ptr;
00816   }
00817 
00818   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00819   {
00820     if (arguments == NULL)
00821     {
00822       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateMassStorageContent::Update() arguments is NULL");
00823       return;
00824     }
00825 
00826     ::boost::lock_guard<boost::mutex> lock(mutex_);
00827     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateMassStorageContent());
00828     msg_ptr->header.stamp = t;
00829     msg_ptr->header.frame_id = "base_link";
00830 
00831 
00832     arg = NULL;
00833     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_MASS_STORAGE_ID, arg);
00834     if (arg)
00835     {
00836       msg_ptr->mass_storage_id = arg->value.U8;
00837     }
00838 
00839     arg = NULL;
00840     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_NBPHOTOS, arg);
00841     if (arg)
00842     {
00843       msg_ptr->nbPhotos = arg->value.U16;
00844     }
00845 
00846     arg = NULL;
00847     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_NBVIDEOS, arg);
00848     if (arg)
00849     {
00850       msg_ptr->nbVideos = arg->value.U16;
00851     }
00852 
00853     arg = NULL;
00854     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_NBPUDS, arg);
00855     if (arg)
00856     {
00857       msg_ptr->nbPuds = arg->value.U16;
00858     }
00859 
00860     arg = NULL;
00861     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_NBCRASHLOGS, arg);
00862     if (arg)
00863     {
00864       msg_ptr->nbCrashLogs = arg->value.U16;
00865     }
00866 
00867     arg = NULL;
00868     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENT_NBRAWPHOTOS, arg);
00869     if (arg)
00870     {
00871       msg_ptr->nbRawPhotos = arg->value.U16;
00872     }
00873 
00874     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00875   }
00876 
00877 };  // CommonCommonStateMassStorageContent
00878 
00879 
00880 // Mass storage content for current run.\n Only counts the files related to the current run (see [RunId](#0-30-0))
00881 class CommonCommonStateMassStorageContentForCurrentRun : public AbstractState
00882 {
00883 private:
00884   ::bebop_msgs::CommonCommonStateMassStorageContentForCurrentRun::Ptr msg_ptr;
00885 
00886 public:
00887 
00888   CommonCommonStateMassStorageContentForCurrentRun(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00889     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENTFORCURRENTRUN)
00890   {
00891     if (priv_nh.getParam("states/enable_commonstate_massstoragecontentforcurrentrun", pub_enabled_) && pub_enabled_)
00892     {
00893       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00894       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateMassStorageContentForCurrentRun>(topic, 10, true);
00895     } // pub_enabled_ is false
00896   }
00897 
00898   ::bebop_msgs::CommonCommonStateMassStorageContentForCurrentRun::ConstPtr GetDataCstPtr() const
00899   {
00900     ::boost::lock_guard<boost::mutex> lock(mutex_);
00901     return msg_ptr;
00902   }
00903 
00904   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00905   {
00906     if (arguments == NULL)
00907     {
00908       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateMassStorageContentForCurrentRun::Update() arguments is NULL");
00909       return;
00910     }
00911 
00912     ::boost::lock_guard<boost::mutex> lock(mutex_);
00913     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateMassStorageContentForCurrentRun());
00914     msg_ptr->header.stamp = t;
00915     msg_ptr->header.frame_id = "base_link";
00916 
00917 
00918     arg = NULL;
00919     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENTFORCURRENTRUN_MASS_STORAGE_ID, arg);
00920     if (arg)
00921     {
00922       msg_ptr->mass_storage_id = arg->value.U8;
00923     }
00924 
00925     arg = NULL;
00926     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENTFORCURRENTRUN_NBPHOTOS, arg);
00927     if (arg)
00928     {
00929       msg_ptr->nbPhotos = arg->value.U16;
00930     }
00931 
00932     arg = NULL;
00933     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENTFORCURRENTRUN_NBVIDEOS, arg);
00934     if (arg)
00935     {
00936       msg_ptr->nbVideos = arg->value.U16;
00937     }
00938 
00939     arg = NULL;
00940     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_MASSSTORAGECONTENTFORCURRENTRUN_NBRAWPHOTOS, arg);
00941     if (arg)
00942     {
00943       msg_ptr->nbRawPhotos = arg->value.U16;
00944     }
00945 
00946     if (pub_enabled_) ros_pub_.publish(msg_ptr);
00947   }
00948 
00949 };  // CommonCommonStateMassStorageContentForCurrentRun
00950 
00951 
00952 // Current or last video recording timestamp.\n Timestamp in milliseconds since 00:00:00 UTC on 1 January 1970.\n **Please note that values dont persist after drone reboot**
00953 class CommonCommonStateVideoRecordingTimestamp : public AbstractState
00954 {
00955 private:
00956   ::bebop_msgs::CommonCommonStateVideoRecordingTimestamp::Ptr msg_ptr;
00957 
00958 public:
00959 
00960   CommonCommonStateVideoRecordingTimestamp(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
00961     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_VIDEORECORDINGTIMESTAMP)
00962   {
00963     if (priv_nh.getParam("states/enable_commonstate_videorecordingtimestamp", pub_enabled_) && pub_enabled_)
00964     {
00965       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
00966       ros_pub_ = nh.advertise<bebop_msgs::CommonCommonStateVideoRecordingTimestamp>(topic, 10, true);
00967     } // pub_enabled_ is false
00968   }
00969 
00970   ::bebop_msgs::CommonCommonStateVideoRecordingTimestamp::ConstPtr GetDataCstPtr() const
00971   {
00972     ::boost::lock_guard<boost::mutex> lock(mutex_);
00973     return msg_ptr;
00974   }
00975 
00976   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
00977   {
00978     if (arguments == NULL)
00979     {
00980       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCommonStateVideoRecordingTimestamp::Update() arguments is NULL");
00981       return;
00982     }
00983 
00984     ::boost::lock_guard<boost::mutex> lock(mutex_);
00985     msg_ptr.reset(new ::bebop_msgs::CommonCommonStateVideoRecordingTimestamp());
00986     msg_ptr->header.stamp = t;
00987     msg_ptr->header.frame_id = "base_link";
00988 
00989 
00990     arg = NULL;
00991     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_VIDEORECORDINGTIMESTAMP_STARTTIMESTAMP, arg);
00992     if (arg)
00993     {
00994       msg_ptr->startTimestamp = arg->value.U64;
00995     }
00996 
00997     arg = NULL;
00998     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_COMMONSTATE_VIDEORECORDINGTIMESTAMP_STOPTIMESTAMP, arg);
00999     if (arg)
01000     {
01001       msg_ptr->stopTimestamp = arg->value.U64;
01002     }
01003 
01004     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01005   }
01006 
01007 };  // CommonCommonStateVideoRecordingTimestamp
01008 
01009 
01010 // Overheat temperature reached.
01011 class CommonOverHeatStateOverHeatChanged : public AbstractState
01012 {
01013 private:
01014   ::bebop_msgs::CommonOverHeatStateOverHeatChanged::Ptr msg_ptr;
01015 
01016 public:
01017 
01018   CommonOverHeatStateOverHeatChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01019     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_OVERHEATSTATE_OVERHEATCHANGED)
01020   {
01021     if (priv_nh.getParam("states/enable_overheatstate_overheatchanged", pub_enabled_) && pub_enabled_)
01022     {
01023       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01024       ros_pub_ = nh.advertise<bebop_msgs::CommonOverHeatStateOverHeatChanged>(topic, 10, true);
01025     } // pub_enabled_ is false
01026   }
01027 
01028   ::bebop_msgs::CommonOverHeatStateOverHeatChanged::ConstPtr GetDataCstPtr() const
01029   {
01030     ::boost::lock_guard<boost::mutex> lock(mutex_);
01031     return msg_ptr;
01032   }
01033 
01034   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01035   {
01036     if (arguments == NULL)
01037     {
01038       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonOverHeatStateOverHeatChanged::Update() arguments is NULL");
01039       return;
01040     }
01041 
01042     ::boost::lock_guard<boost::mutex> lock(mutex_);
01043     msg_ptr.reset(new ::bebop_msgs::CommonOverHeatStateOverHeatChanged());
01044     msg_ptr->header.stamp = t;
01045     msg_ptr->header.frame_id = "base_link";
01046 
01047 
01048     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01049   }
01050 
01051 };  // CommonOverHeatStateOverHeatChanged
01052 
01053 
01054 // Overheat regulation type.
01055 class CommonOverHeatStateOverHeatRegulationChanged : public AbstractState
01056 {
01057 private:
01058   ::bebop_msgs::CommonOverHeatStateOverHeatRegulationChanged::Ptr msg_ptr;
01059 
01060 public:
01061 
01062   CommonOverHeatStateOverHeatRegulationChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01063     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_OVERHEATSTATE_OVERHEATREGULATIONCHANGED)
01064   {
01065     if (priv_nh.getParam("states/enable_overheatstate_overheatregulationchanged", pub_enabled_) && pub_enabled_)
01066     {
01067       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01068       ros_pub_ = nh.advertise<bebop_msgs::CommonOverHeatStateOverHeatRegulationChanged>(topic, 10, true);
01069     } // pub_enabled_ is false
01070   }
01071 
01072   ::bebop_msgs::CommonOverHeatStateOverHeatRegulationChanged::ConstPtr GetDataCstPtr() const
01073   {
01074     ::boost::lock_guard<boost::mutex> lock(mutex_);
01075     return msg_ptr;
01076   }
01077 
01078   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01079   {
01080     if (arguments == NULL)
01081     {
01082       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonOverHeatStateOverHeatRegulationChanged::Update() arguments is NULL");
01083       return;
01084     }
01085 
01086     ::boost::lock_guard<boost::mutex> lock(mutex_);
01087     msg_ptr.reset(new ::bebop_msgs::CommonOverHeatStateOverHeatRegulationChanged());
01088     msg_ptr->header.stamp = t;
01089     msg_ptr->header.frame_id = "base_link";
01090 
01091 
01092     arg = NULL;
01093     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_OVERHEATSTATE_OVERHEATREGULATIONCHANGED_REGULATIONTYPE, arg);
01094     if (arg)
01095     {
01096       msg_ptr->regulationType = arg->value.U8;
01097     }
01098 
01099     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01100   }
01101 
01102 };  // CommonOverHeatStateOverHeatRegulationChanged
01103 
01104 
01105 // Playing state of a FlightPlan.
01106 class CommonMavlinkStateMavlinkFilePlayingStateChanged : public AbstractState
01107 {
01108 private:
01109   ::bebop_msgs::CommonMavlinkStateMavlinkFilePlayingStateChanged::Ptr msg_ptr;
01110 
01111 public:
01112 
01113   CommonMavlinkStateMavlinkFilePlayingStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01114     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKFILEPLAYINGSTATECHANGED)
01115   {
01116     if (priv_nh.getParam("states/enable_mavlinkstate_mavlinkfileplayingstatechanged", pub_enabled_) && pub_enabled_)
01117     {
01118       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01119       ros_pub_ = nh.advertise<bebop_msgs::CommonMavlinkStateMavlinkFilePlayingStateChanged>(topic, 10, true);
01120     } // pub_enabled_ is false
01121   }
01122 
01123   ::bebop_msgs::CommonMavlinkStateMavlinkFilePlayingStateChanged::ConstPtr GetDataCstPtr() const
01124   {
01125     ::boost::lock_guard<boost::mutex> lock(mutex_);
01126     return msg_ptr;
01127   }
01128 
01129   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01130   {
01131     if (arguments == NULL)
01132     {
01133       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonMavlinkStateMavlinkFilePlayingStateChanged::Update() arguments is NULL");
01134       return;
01135     }
01136 
01137     ::boost::lock_guard<boost::mutex> lock(mutex_);
01138     msg_ptr.reset(new ::bebop_msgs::CommonMavlinkStateMavlinkFilePlayingStateChanged());
01139     msg_ptr->header.stamp = t;
01140     msg_ptr->header.frame_id = "base_link";
01141 
01142 
01143     arg = NULL;
01144     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKFILEPLAYINGSTATECHANGED_STATE, arg);
01145     if (arg)
01146     {
01147       msg_ptr->state = arg->value.I32;
01148     }
01149 
01150     arg = NULL;
01151     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKFILEPLAYINGSTATECHANGED_FILEPATH, arg);
01152     if (arg)
01153     {
01154       msg_ptr->filepath = arg->value.String;
01155     }
01156 
01157     arg = NULL;
01158     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKFILEPLAYINGSTATECHANGED_TYPE, arg);
01159     if (arg)
01160     {
01161       msg_ptr->type = arg->value.I32;
01162     }
01163 
01164     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01165   }
01166 
01167 };  // CommonMavlinkStateMavlinkFilePlayingStateChanged
01168 
01169 
01170 // FlightPlan error.
01171 class CommonMavlinkStateMavlinkPlayErrorStateChanged : public AbstractState
01172 {
01173 private:
01174   ::bebop_msgs::CommonMavlinkStateMavlinkPlayErrorStateChanged::Ptr msg_ptr;
01175 
01176 public:
01177 
01178   CommonMavlinkStateMavlinkPlayErrorStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01179     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKPLAYERRORSTATECHANGED)
01180   {
01181     if (priv_nh.getParam("states/enable_mavlinkstate_mavlinkplayerrorstatechanged", pub_enabled_) && pub_enabled_)
01182     {
01183       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01184       ros_pub_ = nh.advertise<bebop_msgs::CommonMavlinkStateMavlinkPlayErrorStateChanged>(topic, 10, true);
01185     } // pub_enabled_ is false
01186   }
01187 
01188   ::bebop_msgs::CommonMavlinkStateMavlinkPlayErrorStateChanged::ConstPtr GetDataCstPtr() const
01189   {
01190     ::boost::lock_guard<boost::mutex> lock(mutex_);
01191     return msg_ptr;
01192   }
01193 
01194   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01195   {
01196     if (arguments == NULL)
01197     {
01198       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonMavlinkStateMavlinkPlayErrorStateChanged::Update() arguments is NULL");
01199       return;
01200     }
01201 
01202     ::boost::lock_guard<boost::mutex> lock(mutex_);
01203     msg_ptr.reset(new ::bebop_msgs::CommonMavlinkStateMavlinkPlayErrorStateChanged());
01204     msg_ptr->header.stamp = t;
01205     msg_ptr->header.frame_id = "base_link";
01206 
01207 
01208     arg = NULL;
01209     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MAVLINKPLAYERRORSTATECHANGED_ERROR, arg);
01210     if (arg)
01211     {
01212       msg_ptr->error = arg->value.I32;
01213     }
01214 
01215     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01216   }
01217 
01218 };  // CommonMavlinkStateMavlinkPlayErrorStateChanged
01219 
01220 
01221 // Mission item has been executed.
01222 class CommonMavlinkStateMissionItemExecuted : public AbstractState
01223 {
01224 private:
01225   ::bebop_msgs::CommonMavlinkStateMissionItemExecuted::Ptr msg_ptr;
01226 
01227 public:
01228 
01229   CommonMavlinkStateMissionItemExecuted(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01230     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSIONITEMEXECUTED)
01231   {
01232     if (priv_nh.getParam("states/enable_mavlinkstate_missionitemexecuted", pub_enabled_) && pub_enabled_)
01233     {
01234       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01235       ros_pub_ = nh.advertise<bebop_msgs::CommonMavlinkStateMissionItemExecuted>(topic, 10, true);
01236     } // pub_enabled_ is false
01237   }
01238 
01239   ::bebop_msgs::CommonMavlinkStateMissionItemExecuted::ConstPtr GetDataCstPtr() const
01240   {
01241     ::boost::lock_guard<boost::mutex> lock(mutex_);
01242     return msg_ptr;
01243   }
01244 
01245   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01246   {
01247     if (arguments == NULL)
01248     {
01249       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonMavlinkStateMissionItemExecuted::Update() arguments is NULL");
01250       return;
01251     }
01252 
01253     ::boost::lock_guard<boost::mutex> lock(mutex_);
01254     msg_ptr.reset(new ::bebop_msgs::CommonMavlinkStateMissionItemExecuted());
01255     msg_ptr->header.stamp = t;
01256     msg_ptr->header.frame_id = "base_link";
01257 
01258 
01259     arg = NULL;
01260     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_MAVLINKSTATE_MISSIONITEMEXECUTED_IDX, arg);
01261     if (arg)
01262     {
01263       msg_ptr->idx = arg->value.U32;
01264     }
01265 
01266     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01267   }
01268 
01269 };  // CommonMavlinkStateMissionItemExecuted
01270 
01271 
01272 // Magneto calib process axis state.
01273 class CommonCalibrationStateMagnetoCalibrationStateChanged : public AbstractState
01274 {
01275 private:
01276   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStateChanged::Ptr msg_ptr;
01277 
01278 public:
01279 
01280   CommonCalibrationStateMagnetoCalibrationStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01281     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTATECHANGED)
01282   {
01283     if (priv_nh.getParam("states/enable_calibrationstate_magnetocalibrationstatechanged", pub_enabled_) && pub_enabled_)
01284     {
01285       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01286       ros_pub_ = nh.advertise<bebop_msgs::CommonCalibrationStateMagnetoCalibrationStateChanged>(topic, 10, true);
01287     } // pub_enabled_ is false
01288   }
01289 
01290   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStateChanged::ConstPtr GetDataCstPtr() const
01291   {
01292     ::boost::lock_guard<boost::mutex> lock(mutex_);
01293     return msg_ptr;
01294   }
01295 
01296   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01297   {
01298     if (arguments == NULL)
01299     {
01300       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCalibrationStateMagnetoCalibrationStateChanged::Update() arguments is NULL");
01301       return;
01302     }
01303 
01304     ::boost::lock_guard<boost::mutex> lock(mutex_);
01305     msg_ptr.reset(new ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStateChanged());
01306     msg_ptr->header.stamp = t;
01307     msg_ptr->header.frame_id = "base_link";
01308 
01309 
01310     arg = NULL;
01311     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTATECHANGED_XAXISCALIBRATION, arg);
01312     if (arg)
01313     {
01314       msg_ptr->xAxisCalibration = arg->value.U8;
01315     }
01316 
01317     arg = NULL;
01318     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTATECHANGED_YAXISCALIBRATION, arg);
01319     if (arg)
01320     {
01321       msg_ptr->yAxisCalibration = arg->value.U8;
01322     }
01323 
01324     arg = NULL;
01325     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTATECHANGED_ZAXISCALIBRATION, arg);
01326     if (arg)
01327     {
01328       msg_ptr->zAxisCalibration = arg->value.U8;
01329     }
01330 
01331     arg = NULL;
01332     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTATECHANGED_CALIBRATIONFAILED, arg);
01333     if (arg)
01334     {
01335       msg_ptr->calibrationFailed = arg->value.U8;
01336     }
01337 
01338     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01339   }
01340 
01341 };  // CommonCalibrationStateMagnetoCalibrationStateChanged
01342 
01343 
01344 // Calibration required.
01345 class CommonCalibrationStateMagnetoCalibrationRequiredState : public AbstractState
01346 {
01347 private:
01348   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationRequiredState::Ptr msg_ptr;
01349 
01350 public:
01351 
01352   CommonCalibrationStateMagnetoCalibrationRequiredState(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01353     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONREQUIREDSTATE)
01354   {
01355     if (priv_nh.getParam("states/enable_calibrationstate_magnetocalibrationrequiredstate", pub_enabled_) && pub_enabled_)
01356     {
01357       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01358       ros_pub_ = nh.advertise<bebop_msgs::CommonCalibrationStateMagnetoCalibrationRequiredState>(topic, 10, true);
01359     } // pub_enabled_ is false
01360   }
01361 
01362   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationRequiredState::ConstPtr GetDataCstPtr() const
01363   {
01364     ::boost::lock_guard<boost::mutex> lock(mutex_);
01365     return msg_ptr;
01366   }
01367 
01368   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01369   {
01370     if (arguments == NULL)
01371     {
01372       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCalibrationStateMagnetoCalibrationRequiredState::Update() arguments is NULL");
01373       return;
01374     }
01375 
01376     ::boost::lock_guard<boost::mutex> lock(mutex_);
01377     msg_ptr.reset(new ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationRequiredState());
01378     msg_ptr->header.stamp = t;
01379     msg_ptr->header.frame_id = "base_link";
01380 
01381 
01382     arg = NULL;
01383     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONREQUIREDSTATE_REQUIRED, arg);
01384     if (arg)
01385     {
01386       msg_ptr->required = arg->value.U8;
01387     }
01388 
01389     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01390   }
01391 
01392 };  // CommonCalibrationStateMagnetoCalibrationRequiredState
01393 
01394 
01395 // Axis to calibrate during calibration process.
01396 class CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged : public AbstractState
01397 {
01398 private:
01399   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged::Ptr msg_ptr;
01400 
01401 public:
01402 
01403   CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01404     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONAXISTOCALIBRATECHANGED)
01405   {
01406     if (priv_nh.getParam("states/enable_calibrationstate_magnetocalibrationaxistocalibratechanged", pub_enabled_) && pub_enabled_)
01407     {
01408       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01409       ros_pub_ = nh.advertise<bebop_msgs::CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged>(topic, 10, true);
01410     } // pub_enabled_ is false
01411   }
01412 
01413   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged::ConstPtr GetDataCstPtr() const
01414   {
01415     ::boost::lock_guard<boost::mutex> lock(mutex_);
01416     return msg_ptr;
01417   }
01418 
01419   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01420   {
01421     if (arguments == NULL)
01422     {
01423       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged::Update() arguments is NULL");
01424       return;
01425     }
01426 
01427     ::boost::lock_guard<boost::mutex> lock(mutex_);
01428     msg_ptr.reset(new ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged());
01429     msg_ptr->header.stamp = t;
01430     msg_ptr->header.frame_id = "base_link";
01431 
01432 
01433     arg = NULL;
01434     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONAXISTOCALIBRATECHANGED_AXIS, arg);
01435     if (arg)
01436     {
01437       msg_ptr->axis = arg->value.I32;
01438     }
01439 
01440     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01441   }
01442 
01443 };  // CommonCalibrationStateMagnetoCalibrationAxisToCalibrateChanged
01444 
01445 
01446 // Calibration process state.
01447 class CommonCalibrationStateMagnetoCalibrationStartedChanged : public AbstractState
01448 {
01449 private:
01450   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStartedChanged::Ptr msg_ptr;
01451 
01452 public:
01453 
01454   CommonCalibrationStateMagnetoCalibrationStartedChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01455     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTARTEDCHANGED)
01456   {
01457     if (priv_nh.getParam("states/enable_calibrationstate_magnetocalibrationstartedchanged", pub_enabled_) && pub_enabled_)
01458     {
01459       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01460       ros_pub_ = nh.advertise<bebop_msgs::CommonCalibrationStateMagnetoCalibrationStartedChanged>(topic, 10, true);
01461     } // pub_enabled_ is false
01462   }
01463 
01464   ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStartedChanged::ConstPtr GetDataCstPtr() const
01465   {
01466     ::boost::lock_guard<boost::mutex> lock(mutex_);
01467     return msg_ptr;
01468   }
01469 
01470   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01471   {
01472     if (arguments == NULL)
01473     {
01474       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCalibrationStateMagnetoCalibrationStartedChanged::Update() arguments is NULL");
01475       return;
01476     }
01477 
01478     ::boost::lock_guard<boost::mutex> lock(mutex_);
01479     msg_ptr.reset(new ::bebop_msgs::CommonCalibrationStateMagnetoCalibrationStartedChanged());
01480     msg_ptr->header.stamp = t;
01481     msg_ptr->header.frame_id = "base_link";
01482 
01483 
01484     arg = NULL;
01485     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_MAGNETOCALIBRATIONSTARTEDCHANGED_STARTED, arg);
01486     if (arg)
01487     {
01488       msg_ptr->started = arg->value.U8;
01489     }
01490 
01491     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01492   }
01493 
01494 };  // CommonCalibrationStateMagnetoCalibrationStartedChanged
01495 
01496 
01497 // 
01498 class CommonCalibrationStatePitotCalibrationStateChanged : public AbstractState
01499 {
01500 private:
01501   ::bebop_msgs::CommonCalibrationStatePitotCalibrationStateChanged::Ptr msg_ptr;
01502 
01503 public:
01504 
01505   CommonCalibrationStatePitotCalibrationStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01506     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_PITOTCALIBRATIONSTATECHANGED)
01507   {
01508     if (priv_nh.getParam("states/enable_calibrationstate_pitotcalibrationstatechanged", pub_enabled_) && pub_enabled_)
01509     {
01510       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01511       ros_pub_ = nh.advertise<bebop_msgs::CommonCalibrationStatePitotCalibrationStateChanged>(topic, 10, true);
01512     } // pub_enabled_ is false
01513   }
01514 
01515   ::bebop_msgs::CommonCalibrationStatePitotCalibrationStateChanged::ConstPtr GetDataCstPtr() const
01516   {
01517     ::boost::lock_guard<boost::mutex> lock(mutex_);
01518     return msg_ptr;
01519   }
01520 
01521   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01522   {
01523     if (arguments == NULL)
01524     {
01525       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonCalibrationStatePitotCalibrationStateChanged::Update() arguments is NULL");
01526       return;
01527     }
01528 
01529     ::boost::lock_guard<boost::mutex> lock(mutex_);
01530     msg_ptr.reset(new ::bebop_msgs::CommonCalibrationStatePitotCalibrationStateChanged());
01531     msg_ptr->header.stamp = t;
01532     msg_ptr->header.frame_id = "base_link";
01533 
01534 
01535     arg = NULL;
01536     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_PITOTCALIBRATIONSTATECHANGED_STATE, arg);
01537     if (arg)
01538     {
01539       msg_ptr->state = arg->value.I32;
01540     }
01541 
01542     arg = NULL;
01543     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CALIBRATIONSTATE_PITOTCALIBRATIONSTATECHANGED_LASTERROR, arg);
01544     if (arg)
01545     {
01546       msg_ptr->lastError = arg->value.U8;
01547     }
01548 
01549     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01550   }
01551 
01552 };  // CommonCalibrationStatePitotCalibrationStateChanged
01553 
01554 
01555 // FlightPlan availability.\n Availability is linked to GPS fix, magnetometer calibration, sensor states...
01556 class CommonFlightPlanStateAvailabilityStateChanged : public AbstractState
01557 {
01558 private:
01559   ::bebop_msgs::CommonFlightPlanStateAvailabilityStateChanged::Ptr msg_ptr;
01560 
01561 public:
01562 
01563   CommonFlightPlanStateAvailabilityStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01564     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_AVAILABILITYSTATECHANGED)
01565   {
01566     if (priv_nh.getParam("states/enable_flightplanstate_availabilitystatechanged", pub_enabled_) && pub_enabled_)
01567     {
01568       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01569       ros_pub_ = nh.advertise<bebop_msgs::CommonFlightPlanStateAvailabilityStateChanged>(topic, 10, true);
01570     } // pub_enabled_ is false
01571   }
01572 
01573   ::bebop_msgs::CommonFlightPlanStateAvailabilityStateChanged::ConstPtr GetDataCstPtr() const
01574   {
01575     ::boost::lock_guard<boost::mutex> lock(mutex_);
01576     return msg_ptr;
01577   }
01578 
01579   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01580   {
01581     if (arguments == NULL)
01582     {
01583       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonFlightPlanStateAvailabilityStateChanged::Update() arguments is NULL");
01584       return;
01585     }
01586 
01587     ::boost::lock_guard<boost::mutex> lock(mutex_);
01588     msg_ptr.reset(new ::bebop_msgs::CommonFlightPlanStateAvailabilityStateChanged());
01589     msg_ptr->header.stamp = t;
01590     msg_ptr->header.frame_id = "base_link";
01591 
01592 
01593     arg = NULL;
01594     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_AVAILABILITYSTATECHANGED_AVAILABILITYSTATE, arg);
01595     if (arg)
01596     {
01597       msg_ptr->AvailabilityState = arg->value.U8;
01598     }
01599 
01600     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01601   }
01602 
01603 };  // CommonFlightPlanStateAvailabilityStateChanged
01604 
01605 
01606 // FlightPlan components state list.
01607 class CommonFlightPlanStateComponentStateListChanged : public AbstractState
01608 {
01609 private:
01610   ::bebop_msgs::CommonFlightPlanStateComponentStateListChanged::Ptr msg_ptr;
01611 
01612 public:
01613 
01614   CommonFlightPlanStateComponentStateListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01615     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_COMPONENTSTATELISTCHANGED)
01616   {
01617     if (priv_nh.getParam("states/enable_flightplanstate_componentstatelistchanged", pub_enabled_) && pub_enabled_)
01618     {
01619       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01620       ros_pub_ = nh.advertise<bebop_msgs::CommonFlightPlanStateComponentStateListChanged>(topic, 10, true);
01621     } // pub_enabled_ is false
01622   }
01623 
01624   ::bebop_msgs::CommonFlightPlanStateComponentStateListChanged::ConstPtr GetDataCstPtr() const
01625   {
01626     ::boost::lock_guard<boost::mutex> lock(mutex_);
01627     return msg_ptr;
01628   }
01629 
01630   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01631   {
01632     if (arguments == NULL)
01633     {
01634       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonFlightPlanStateComponentStateListChanged::Update() arguments is NULL");
01635       return;
01636     }
01637 
01638     ::boost::lock_guard<boost::mutex> lock(mutex_);
01639     msg_ptr.reset(new ::bebop_msgs::CommonFlightPlanStateComponentStateListChanged());
01640     msg_ptr->header.stamp = t;
01641     msg_ptr->header.frame_id = "base_link";
01642 
01643 
01644     arg = NULL;
01645     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_COMPONENTSTATELISTCHANGED_COMPONENT, arg);
01646     if (arg)
01647     {
01648       msg_ptr->component = arg->value.I32;
01649     }
01650 
01651     arg = NULL;
01652     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_COMPONENTSTATELISTCHANGED_STATE, arg);
01653     if (arg)
01654     {
01655       msg_ptr->State = arg->value.U8;
01656     }
01657 
01658     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01659   }
01660 
01661 };  // CommonFlightPlanStateComponentStateListChanged
01662 
01663 
01664 // FlightPlan lock state.\n Represents the fact that the controller is able or not to stop or pause a playing FlightPlan
01665 class CommonFlightPlanStateLockStateChanged : public AbstractState
01666 {
01667 private:
01668   ::bebop_msgs::CommonFlightPlanStateLockStateChanged::Ptr msg_ptr;
01669 
01670 public:
01671 
01672   CommonFlightPlanStateLockStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01673     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_LOCKSTATECHANGED)
01674   {
01675     if (priv_nh.getParam("states/enable_flightplanstate_lockstatechanged", pub_enabled_) && pub_enabled_)
01676     {
01677       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01678       ros_pub_ = nh.advertise<bebop_msgs::CommonFlightPlanStateLockStateChanged>(topic, 10, true);
01679     } // pub_enabled_ is false
01680   }
01681 
01682   ::bebop_msgs::CommonFlightPlanStateLockStateChanged::ConstPtr GetDataCstPtr() const
01683   {
01684     ::boost::lock_guard<boost::mutex> lock(mutex_);
01685     return msg_ptr;
01686   }
01687 
01688   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01689   {
01690     if (arguments == NULL)
01691     {
01692       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonFlightPlanStateLockStateChanged::Update() arguments is NULL");
01693       return;
01694     }
01695 
01696     ::boost::lock_guard<boost::mutex> lock(mutex_);
01697     msg_ptr.reset(new ::bebop_msgs::CommonFlightPlanStateLockStateChanged());
01698     msg_ptr->header.stamp = t;
01699     msg_ptr->header.frame_id = "base_link";
01700 
01701 
01702     arg = NULL;
01703     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_FLIGHTPLANSTATE_LOCKSTATECHANGED_LOCKSTATE, arg);
01704     if (arg)
01705     {
01706       msg_ptr->LockState = arg->value.U8;
01707     }
01708 
01709     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01710   }
01711 
01712 };  // CommonFlightPlanStateLockStateChanged
01713 
01714 
01715 // 
01716 class CommonARLibsVersionsStateControllerLibARCommandsVersion : public AbstractState
01717 {
01718 private:
01719   ::bebop_msgs::CommonARLibsVersionsStateControllerLibARCommandsVersion::Ptr msg_ptr;
01720 
01721 public:
01722 
01723   CommonARLibsVersionsStateControllerLibARCommandsVersion(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01724     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_CONTROLLERLIBARCOMMANDSVERSION)
01725   {
01726     if (priv_nh.getParam("states/enable_arlibsversionsstate_controllerlibarcommandsversion", pub_enabled_) && pub_enabled_)
01727     {
01728       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01729       ros_pub_ = nh.advertise<bebop_msgs::CommonARLibsVersionsStateControllerLibARCommandsVersion>(topic, 10, true);
01730     } // pub_enabled_ is false
01731   }
01732 
01733   ::bebop_msgs::CommonARLibsVersionsStateControllerLibARCommandsVersion::ConstPtr GetDataCstPtr() const
01734   {
01735     ::boost::lock_guard<boost::mutex> lock(mutex_);
01736     return msg_ptr;
01737   }
01738 
01739   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01740   {
01741     if (arguments == NULL)
01742     {
01743       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonARLibsVersionsStateControllerLibARCommandsVersion::Update() arguments is NULL");
01744       return;
01745     }
01746 
01747     ::boost::lock_guard<boost::mutex> lock(mutex_);
01748     msg_ptr.reset(new ::bebop_msgs::CommonARLibsVersionsStateControllerLibARCommandsVersion());
01749     msg_ptr->header.stamp = t;
01750     msg_ptr->header.frame_id = "base_link";
01751 
01752 
01753     arg = NULL;
01754     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_CONTROLLERLIBARCOMMANDSVERSION_VERSION, arg);
01755     if (arg)
01756     {
01757       msg_ptr->version = arg->value.String;
01758     }
01759 
01760     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01761   }
01762 
01763 };  // CommonARLibsVersionsStateControllerLibARCommandsVersion
01764 
01765 
01766 // 
01767 class CommonARLibsVersionsStateSkyControllerLibARCommandsVersion : public AbstractState
01768 {
01769 private:
01770   ::bebop_msgs::CommonARLibsVersionsStateSkyControllerLibARCommandsVersion::Ptr msg_ptr;
01771 
01772 public:
01773 
01774   CommonARLibsVersionsStateSkyControllerLibARCommandsVersion(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01775     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_SKYCONTROLLERLIBARCOMMANDSVERSION)
01776   {
01777     if (priv_nh.getParam("states/enable_arlibsversionsstate_skycontrollerlibarcommandsversion", pub_enabled_) && pub_enabled_)
01778     {
01779       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01780       ros_pub_ = nh.advertise<bebop_msgs::CommonARLibsVersionsStateSkyControllerLibARCommandsVersion>(topic, 10, true);
01781     } // pub_enabled_ is false
01782   }
01783 
01784   ::bebop_msgs::CommonARLibsVersionsStateSkyControllerLibARCommandsVersion::ConstPtr GetDataCstPtr() const
01785   {
01786     ::boost::lock_guard<boost::mutex> lock(mutex_);
01787     return msg_ptr;
01788   }
01789 
01790   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01791   {
01792     if (arguments == NULL)
01793     {
01794       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonARLibsVersionsStateSkyControllerLibARCommandsVersion::Update() arguments is NULL");
01795       return;
01796     }
01797 
01798     ::boost::lock_guard<boost::mutex> lock(mutex_);
01799     msg_ptr.reset(new ::bebop_msgs::CommonARLibsVersionsStateSkyControllerLibARCommandsVersion());
01800     msg_ptr->header.stamp = t;
01801     msg_ptr->header.frame_id = "base_link";
01802 
01803 
01804     arg = NULL;
01805     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_SKYCONTROLLERLIBARCOMMANDSVERSION_VERSION, arg);
01806     if (arg)
01807     {
01808       msg_ptr->version = arg->value.String;
01809     }
01810 
01811     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01812   }
01813 
01814 };  // CommonARLibsVersionsStateSkyControllerLibARCommandsVersion
01815 
01816 
01817 // 
01818 class CommonARLibsVersionsStateDeviceLibARCommandsVersion : public AbstractState
01819 {
01820 private:
01821   ::bebop_msgs::CommonARLibsVersionsStateDeviceLibARCommandsVersion::Ptr msg_ptr;
01822 
01823 public:
01824 
01825   CommonARLibsVersionsStateDeviceLibARCommandsVersion(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01826     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_DEVICELIBARCOMMANDSVERSION)
01827   {
01828     if (priv_nh.getParam("states/enable_arlibsversionsstate_devicelibarcommandsversion", pub_enabled_) && pub_enabled_)
01829     {
01830       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01831       ros_pub_ = nh.advertise<bebop_msgs::CommonARLibsVersionsStateDeviceLibARCommandsVersion>(topic, 10, true);
01832     } // pub_enabled_ is false
01833   }
01834 
01835   ::bebop_msgs::CommonARLibsVersionsStateDeviceLibARCommandsVersion::ConstPtr GetDataCstPtr() const
01836   {
01837     ::boost::lock_guard<boost::mutex> lock(mutex_);
01838     return msg_ptr;
01839   }
01840 
01841   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01842   {
01843     if (arguments == NULL)
01844     {
01845       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonARLibsVersionsStateDeviceLibARCommandsVersion::Update() arguments is NULL");
01846       return;
01847     }
01848 
01849     ::boost::lock_guard<boost::mutex> lock(mutex_);
01850     msg_ptr.reset(new ::bebop_msgs::CommonARLibsVersionsStateDeviceLibARCommandsVersion());
01851     msg_ptr->header.stamp = t;
01852     msg_ptr->header.frame_id = "base_link";
01853 
01854 
01855     arg = NULL;
01856     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ARLIBSVERSIONSSTATE_DEVICELIBARCOMMANDSVERSION_VERSION, arg);
01857     if (arg)
01858     {
01859       msg_ptr->version = arg->value.String;
01860     }
01861 
01862     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01863   }
01864 
01865 };  // CommonARLibsVersionsStateDeviceLibARCommandsVersion
01866 
01867 
01868 // Audio stream direction.
01869 class CommonAudioStateAudioStreamingRunning : public AbstractState
01870 {
01871 private:
01872   ::bebop_msgs::CommonAudioStateAudioStreamingRunning::Ptr msg_ptr;
01873 
01874 public:
01875 
01876   CommonAudioStateAudioStreamingRunning(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01877     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_AUDIOSTATE_AUDIOSTREAMINGRUNNING)
01878   {
01879     if (priv_nh.getParam("states/enable_audiostate_audiostreamingrunning", pub_enabled_) && pub_enabled_)
01880     {
01881       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01882       ros_pub_ = nh.advertise<bebop_msgs::CommonAudioStateAudioStreamingRunning>(topic, 10, true);
01883     } // pub_enabled_ is false
01884   }
01885 
01886   ::bebop_msgs::CommonAudioStateAudioStreamingRunning::ConstPtr GetDataCstPtr() const
01887   {
01888     ::boost::lock_guard<boost::mutex> lock(mutex_);
01889     return msg_ptr;
01890   }
01891 
01892   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01893   {
01894     if (arguments == NULL)
01895     {
01896       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonAudioStateAudioStreamingRunning::Update() arguments is NULL");
01897       return;
01898     }
01899 
01900     ::boost::lock_guard<boost::mutex> lock(mutex_);
01901     msg_ptr.reset(new ::bebop_msgs::CommonAudioStateAudioStreamingRunning());
01902     msg_ptr->header.stamp = t;
01903     msg_ptr->header.frame_id = "base_link";
01904 
01905 
01906     arg = NULL;
01907     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_AUDIOSTATE_AUDIOSTREAMINGRUNNING_RUNNING, arg);
01908     if (arg)
01909     {
01910       msg_ptr->running = arg->value.U8;
01911     }
01912 
01913     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01914   }
01915 
01916 };  // CommonAudioStateAudioStreamingRunning
01917 
01918 
01919 // Lighting LEDs intensity.
01920 class CommonHeadlightsStateintensityChanged : public AbstractState
01921 {
01922 private:
01923   ::bebop_msgs::CommonHeadlightsStateintensityChanged::Ptr msg_ptr;
01924 
01925 public:
01926 
01927   CommonHeadlightsStateintensityChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01928     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_HEADLIGHTSSTATE_INTENSITYCHANGED)
01929   {
01930     if (priv_nh.getParam("states/enable_headlightsstate_intensitychanged", pub_enabled_) && pub_enabled_)
01931     {
01932       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01933       ros_pub_ = nh.advertise<bebop_msgs::CommonHeadlightsStateintensityChanged>(topic, 10, true);
01934     } // pub_enabled_ is false
01935   }
01936 
01937   ::bebop_msgs::CommonHeadlightsStateintensityChanged::ConstPtr GetDataCstPtr() const
01938   {
01939     ::boost::lock_guard<boost::mutex> lock(mutex_);
01940     return msg_ptr;
01941   }
01942 
01943   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
01944   {
01945     if (arguments == NULL)
01946     {
01947       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonHeadlightsStateintensityChanged::Update() arguments is NULL");
01948       return;
01949     }
01950 
01951     ::boost::lock_guard<boost::mutex> lock(mutex_);
01952     msg_ptr.reset(new ::bebop_msgs::CommonHeadlightsStateintensityChanged());
01953     msg_ptr->header.stamp = t;
01954     msg_ptr->header.frame_id = "base_link";
01955 
01956 
01957     arg = NULL;
01958     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_HEADLIGHTSSTATE_INTENSITYCHANGED_LEFT, arg);
01959     if (arg)
01960     {
01961       msg_ptr->left = arg->value.U8;
01962     }
01963 
01964     arg = NULL;
01965     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_HEADLIGHTSSTATE_INTENSITYCHANGED_RIGHT, arg);
01966     if (arg)
01967     {
01968       msg_ptr->right = arg->value.U8;
01969     }
01970 
01971     if (pub_enabled_) ros_pub_.publish(msg_ptr);
01972   }
01973 
01974 };  // CommonHeadlightsStateintensityChanged
01975 
01976 
01977 // Paramaterless animations state list.
01978 class CommonAnimationsStateList : public AbstractState
01979 {
01980 private:
01981   ::bebop_msgs::CommonAnimationsStateList::Ptr msg_ptr;
01982 
01983 public:
01984 
01985   CommonAnimationsStateList(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
01986     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ANIMATIONSSTATE_LIST)
01987   {
01988     if (priv_nh.getParam("states/enable_animationsstate_list", pub_enabled_) && pub_enabled_)
01989     {
01990       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
01991       ros_pub_ = nh.advertise<bebop_msgs::CommonAnimationsStateList>(topic, 10, true);
01992     } // pub_enabled_ is false
01993   }
01994 
01995   ::bebop_msgs::CommonAnimationsStateList::ConstPtr GetDataCstPtr() const
01996   {
01997     ::boost::lock_guard<boost::mutex> lock(mutex_);
01998     return msg_ptr;
01999   }
02000 
02001   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02002   {
02003     if (arguments == NULL)
02004     {
02005       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonAnimationsStateList::Update() arguments is NULL");
02006       return;
02007     }
02008 
02009     ::boost::lock_guard<boost::mutex> lock(mutex_);
02010     msg_ptr.reset(new ::bebop_msgs::CommonAnimationsStateList());
02011     msg_ptr->header.stamp = t;
02012     msg_ptr->header.frame_id = "base_link";
02013 
02014 
02015     arg = NULL;
02016     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ANIMATIONSSTATE_LIST_ANIM, arg);
02017     if (arg)
02018     {
02019       msg_ptr->anim = arg->value.I32;
02020     }
02021 
02022     arg = NULL;
02023     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ANIMATIONSSTATE_LIST_STATE, arg);
02024     if (arg)
02025     {
02026       msg_ptr->state = arg->value.I32;
02027     }
02028 
02029     arg = NULL;
02030     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ANIMATIONSSTATE_LIST_ERROR, arg);
02031     if (arg)
02032     {
02033       msg_ptr->error = arg->value.I32;
02034     }
02035 
02036     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02037   }
02038 
02039 };  // CommonAnimationsStateList
02040 
02041 
02042 // Supported accessories list.
02043 class CommonAccessoryStateSupportedAccessoriesListChanged : public AbstractState
02044 {
02045 private:
02046   ::bebop_msgs::CommonAccessoryStateSupportedAccessoriesListChanged::Ptr msg_ptr;
02047 
02048 public:
02049 
02050   CommonAccessoryStateSupportedAccessoriesListChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02051     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_SUPPORTEDACCESSORIESLISTCHANGED)
02052   {
02053     if (priv_nh.getParam("states/enable_accessorystate_supportedaccessorieslistchanged", pub_enabled_) && pub_enabled_)
02054     {
02055       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02056       ros_pub_ = nh.advertise<bebop_msgs::CommonAccessoryStateSupportedAccessoriesListChanged>(topic, 10, true);
02057     } // pub_enabled_ is false
02058   }
02059 
02060   ::bebop_msgs::CommonAccessoryStateSupportedAccessoriesListChanged::ConstPtr GetDataCstPtr() const
02061   {
02062     ::boost::lock_guard<boost::mutex> lock(mutex_);
02063     return msg_ptr;
02064   }
02065 
02066   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02067   {
02068     if (arguments == NULL)
02069     {
02070       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonAccessoryStateSupportedAccessoriesListChanged::Update() arguments is NULL");
02071       return;
02072     }
02073 
02074     ::boost::lock_guard<boost::mutex> lock(mutex_);
02075     msg_ptr.reset(new ::bebop_msgs::CommonAccessoryStateSupportedAccessoriesListChanged());
02076     msg_ptr->header.stamp = t;
02077     msg_ptr->header.frame_id = "base_link";
02078 
02079 
02080     arg = NULL;
02081     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_SUPPORTEDACCESSORIESLISTCHANGED_ACCESSORY, arg);
02082     if (arg)
02083     {
02084       msg_ptr->accessory = arg->value.I32;
02085     }
02086 
02087     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02088   }
02089 
02090 };  // CommonAccessoryStateSupportedAccessoriesListChanged
02091 
02092 
02093 // Accessory config.
02094 class CommonAccessoryStateAccessoryConfigChanged : public AbstractState
02095 {
02096 private:
02097   ::bebop_msgs::CommonAccessoryStateAccessoryConfigChanged::Ptr msg_ptr;
02098 
02099 public:
02100 
02101   CommonAccessoryStateAccessoryConfigChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02102     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_ACCESSORYCONFIGCHANGED)
02103   {
02104     if (priv_nh.getParam("states/enable_accessorystate_accessoryconfigchanged", pub_enabled_) && pub_enabled_)
02105     {
02106       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02107       ros_pub_ = nh.advertise<bebop_msgs::CommonAccessoryStateAccessoryConfigChanged>(topic, 10, true);
02108     } // pub_enabled_ is false
02109   }
02110 
02111   ::bebop_msgs::CommonAccessoryStateAccessoryConfigChanged::ConstPtr GetDataCstPtr() const
02112   {
02113     ::boost::lock_guard<boost::mutex> lock(mutex_);
02114     return msg_ptr;
02115   }
02116 
02117   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02118   {
02119     if (arguments == NULL)
02120     {
02121       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonAccessoryStateAccessoryConfigChanged::Update() arguments is NULL");
02122       return;
02123     }
02124 
02125     ::boost::lock_guard<boost::mutex> lock(mutex_);
02126     msg_ptr.reset(new ::bebop_msgs::CommonAccessoryStateAccessoryConfigChanged());
02127     msg_ptr->header.stamp = t;
02128     msg_ptr->header.frame_id = "base_link";
02129 
02130 
02131     arg = NULL;
02132     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_ACCESSORYCONFIGCHANGED_NEWACCESSORY, arg);
02133     if (arg)
02134     {
02135       msg_ptr->newAccessory = arg->value.I32;
02136     }
02137 
02138     arg = NULL;
02139     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_ACCESSORYCONFIGCHANGED_ERROR, arg);
02140     if (arg)
02141     {
02142       msg_ptr->error = arg->value.I32;
02143     }
02144 
02145     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02146   }
02147 
02148 };  // CommonAccessoryStateAccessoryConfigChanged
02149 
02150 
02151 // Availability to declare or not an accessory.
02152 class CommonAccessoryStateAccessoryConfigModificationEnabled : public AbstractState
02153 {
02154 private:
02155   ::bebop_msgs::CommonAccessoryStateAccessoryConfigModificationEnabled::Ptr msg_ptr;
02156 
02157 public:
02158 
02159   CommonAccessoryStateAccessoryConfigModificationEnabled(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02160     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_ACCESSORYCONFIGMODIFICATIONENABLED)
02161   {
02162     if (priv_nh.getParam("states/enable_accessorystate_accessoryconfigmodificationenabled", pub_enabled_) && pub_enabled_)
02163     {
02164       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02165       ros_pub_ = nh.advertise<bebop_msgs::CommonAccessoryStateAccessoryConfigModificationEnabled>(topic, 10, true);
02166     } // pub_enabled_ is false
02167   }
02168 
02169   ::bebop_msgs::CommonAccessoryStateAccessoryConfigModificationEnabled::ConstPtr GetDataCstPtr() const
02170   {
02171     ::boost::lock_guard<boost::mutex> lock(mutex_);
02172     return msg_ptr;
02173   }
02174 
02175   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02176   {
02177     if (arguments == NULL)
02178     {
02179       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonAccessoryStateAccessoryConfigModificationEnabled::Update() arguments is NULL");
02180       return;
02181     }
02182 
02183     ::boost::lock_guard<boost::mutex> lock(mutex_);
02184     msg_ptr.reset(new ::bebop_msgs::CommonAccessoryStateAccessoryConfigModificationEnabled());
02185     msg_ptr->header.stamp = t;
02186     msg_ptr->header.frame_id = "base_link";
02187 
02188 
02189     arg = NULL;
02190     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_ACCESSORYSTATE_ACCESSORYCONFIGMODIFICATIONENABLED_ENABLED, arg);
02191     if (arg)
02192     {
02193       msg_ptr->enabled = arg->value.U8;
02194     }
02195 
02196     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02197   }
02198 
02199 };  // CommonAccessoryStateAccessoryConfigModificationEnabled
02200 
02201 
02202 // Max charge rate.
02203 class CommonChargerStateMaxChargeRateChanged : public AbstractState
02204 {
02205 private:
02206   ::bebop_msgs::CommonChargerStateMaxChargeRateChanged::Ptr msg_ptr;
02207 
02208 public:
02209 
02210   CommonChargerStateMaxChargeRateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02211     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_MAXCHARGERATECHANGED)
02212   {
02213     if (priv_nh.getParam("states/enable_chargerstate_maxchargeratechanged", pub_enabled_) && pub_enabled_)
02214     {
02215       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02216       ros_pub_ = nh.advertise<bebop_msgs::CommonChargerStateMaxChargeRateChanged>(topic, 10, true);
02217     } // pub_enabled_ is false
02218   }
02219 
02220   ::bebop_msgs::CommonChargerStateMaxChargeRateChanged::ConstPtr GetDataCstPtr() const
02221   {
02222     ::boost::lock_guard<boost::mutex> lock(mutex_);
02223     return msg_ptr;
02224   }
02225 
02226   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02227   {
02228     if (arguments == NULL)
02229     {
02230       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonChargerStateMaxChargeRateChanged::Update() arguments is NULL");
02231       return;
02232     }
02233 
02234     ::boost::lock_guard<boost::mutex> lock(mutex_);
02235     msg_ptr.reset(new ::bebop_msgs::CommonChargerStateMaxChargeRateChanged());
02236     msg_ptr->header.stamp = t;
02237     msg_ptr->header.frame_id = "base_link";
02238 
02239 
02240     arg = NULL;
02241     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_MAXCHARGERATECHANGED_RATE, arg);
02242     if (arg)
02243     {
02244       msg_ptr->rate = arg->value.I32;
02245     }
02246 
02247     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02248   }
02249 
02250 };  // CommonChargerStateMaxChargeRateChanged
02251 
02252 
02253 // Current charge state.
02254 class CommonChargerStateCurrentChargeStateChanged : public AbstractState
02255 {
02256 private:
02257   ::bebop_msgs::CommonChargerStateCurrentChargeStateChanged::Ptr msg_ptr;
02258 
02259 public:
02260 
02261   CommonChargerStateCurrentChargeStateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02262     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CURRENTCHARGESTATECHANGED)
02263   {
02264     if (priv_nh.getParam("states/enable_chargerstate_currentchargestatechanged", pub_enabled_) && pub_enabled_)
02265     {
02266       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02267       ros_pub_ = nh.advertise<bebop_msgs::CommonChargerStateCurrentChargeStateChanged>(topic, 10, true);
02268     } // pub_enabled_ is false
02269   }
02270 
02271   ::bebop_msgs::CommonChargerStateCurrentChargeStateChanged::ConstPtr GetDataCstPtr() const
02272   {
02273     ::boost::lock_guard<boost::mutex> lock(mutex_);
02274     return msg_ptr;
02275   }
02276 
02277   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02278   {
02279     if (arguments == NULL)
02280     {
02281       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonChargerStateCurrentChargeStateChanged::Update() arguments is NULL");
02282       return;
02283     }
02284 
02285     ::boost::lock_guard<boost::mutex> lock(mutex_);
02286     msg_ptr.reset(new ::bebop_msgs::CommonChargerStateCurrentChargeStateChanged());
02287     msg_ptr->header.stamp = t;
02288     msg_ptr->header.frame_id = "base_link";
02289 
02290 
02291     arg = NULL;
02292     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CURRENTCHARGESTATECHANGED_STATUS, arg);
02293     if (arg)
02294     {
02295       msg_ptr->status = arg->value.I32;
02296     }
02297 
02298     arg = NULL;
02299     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CURRENTCHARGESTATECHANGED_PHASE, arg);
02300     if (arg)
02301     {
02302       msg_ptr->phase = arg->value.I32;
02303     }
02304 
02305     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02306   }
02307 
02308 };  // CommonChargerStateCurrentChargeStateChanged
02309 
02310 
02311 // Last charge rate.
02312 class CommonChargerStateLastChargeRateChanged : public AbstractState
02313 {
02314 private:
02315   ::bebop_msgs::CommonChargerStateLastChargeRateChanged::Ptr msg_ptr;
02316 
02317 public:
02318 
02319   CommonChargerStateLastChargeRateChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02320     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_LASTCHARGERATECHANGED)
02321   {
02322     if (priv_nh.getParam("states/enable_chargerstate_lastchargeratechanged", pub_enabled_) && pub_enabled_)
02323     {
02324       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02325       ros_pub_ = nh.advertise<bebop_msgs::CommonChargerStateLastChargeRateChanged>(topic, 10, true);
02326     } // pub_enabled_ is false
02327   }
02328 
02329   ::bebop_msgs::CommonChargerStateLastChargeRateChanged::ConstPtr GetDataCstPtr() const
02330   {
02331     ::boost::lock_guard<boost::mutex> lock(mutex_);
02332     return msg_ptr;
02333   }
02334 
02335   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02336   {
02337     if (arguments == NULL)
02338     {
02339       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonChargerStateLastChargeRateChanged::Update() arguments is NULL");
02340       return;
02341     }
02342 
02343     ::boost::lock_guard<boost::mutex> lock(mutex_);
02344     msg_ptr.reset(new ::bebop_msgs::CommonChargerStateLastChargeRateChanged());
02345     msg_ptr->header.stamp = t;
02346     msg_ptr->header.frame_id = "base_link";
02347 
02348 
02349     arg = NULL;
02350     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_LASTCHARGERATECHANGED_RATE, arg);
02351     if (arg)
02352     {
02353       msg_ptr->rate = arg->value.I32;
02354     }
02355 
02356     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02357   }
02358 
02359 };  // CommonChargerStateLastChargeRateChanged
02360 
02361 
02362 // Charging information.
02363 class CommonChargerStateChargingInfo : public AbstractState
02364 {
02365 private:
02366   ::bebop_msgs::CommonChargerStateChargingInfo::Ptr msg_ptr;
02367 
02368 public:
02369 
02370   CommonChargerStateChargingInfo(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02371     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CHARGINGINFO)
02372   {
02373     if (priv_nh.getParam("states/enable_chargerstate_charginginfo", pub_enabled_) && pub_enabled_)
02374     {
02375       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02376       ros_pub_ = nh.advertise<bebop_msgs::CommonChargerStateChargingInfo>(topic, 10, true);
02377     } // pub_enabled_ is false
02378   }
02379 
02380   ::bebop_msgs::CommonChargerStateChargingInfo::ConstPtr GetDataCstPtr() const
02381   {
02382     ::boost::lock_guard<boost::mutex> lock(mutex_);
02383     return msg_ptr;
02384   }
02385 
02386   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02387   {
02388     if (arguments == NULL)
02389     {
02390       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonChargerStateChargingInfo::Update() arguments is NULL");
02391       return;
02392     }
02393 
02394     ::boost::lock_guard<boost::mutex> lock(mutex_);
02395     msg_ptr.reset(new ::bebop_msgs::CommonChargerStateChargingInfo());
02396     msg_ptr->header.stamp = t;
02397     msg_ptr->header.frame_id = "base_link";
02398 
02399 
02400     arg = NULL;
02401     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CHARGINGINFO_PHASE, arg);
02402     if (arg)
02403     {
02404       msg_ptr->phase = arg->value.I32;
02405     }
02406 
02407     arg = NULL;
02408     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CHARGINGINFO_RATE, arg);
02409     if (arg)
02410     {
02411       msg_ptr->rate = arg->value.I32;
02412     }
02413 
02414     arg = NULL;
02415     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CHARGINGINFO_INTENSITY, arg);
02416     if (arg)
02417     {
02418       msg_ptr->intensity = arg->value.U8;
02419     }
02420 
02421     arg = NULL;
02422     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_CHARGERSTATE_CHARGINGINFO_FULLCHARGINGTIME, arg);
02423     if (arg)
02424     {
02425       msg_ptr->fullChargingTime = arg->value.U8;
02426     }
02427 
02428     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02429   }
02430 
02431 };  // CommonChargerStateChargingInfo
02432 
02433 
02434 // Current run id.\n A run id is uniquely identifying a run or a flight.\n For each run is generated on the drone a file which can be used by Academy to sum up the run.\n Also, each medias taken during a run has a filename containing the run id.
02435 class CommonRunStateRunIdChanged : public AbstractState
02436 {
02437 private:
02438   ::bebop_msgs::CommonRunStateRunIdChanged::Ptr msg_ptr;
02439 
02440 public:
02441 
02442   CommonRunStateRunIdChanged(::ros::NodeHandle& nh, ::ros::NodeHandle& priv_nh, const ::std::string& topic)
02443     : AbstractState(ARCONTROLLER_DICTIONARY_KEY_COMMON_RUNSTATE_RUNIDCHANGED)
02444   {
02445     if (priv_nh.getParam("states/enable_runstate_runidchanged", pub_enabled_) && pub_enabled_)
02446     {
02447       ARSAL_PRINT(ARSAL_PRINT_INFO, "CB" , "[STATES] Enabling %s", topic.c_str());
02448       ros_pub_ = nh.advertise<bebop_msgs::CommonRunStateRunIdChanged>(topic, 10, true);
02449     } // pub_enabled_ is false
02450   }
02451 
02452   ::bebop_msgs::CommonRunStateRunIdChanged::ConstPtr GetDataCstPtr() const
02453   {
02454     ::boost::lock_guard<boost::mutex> lock(mutex_);
02455     return msg_ptr;
02456   }
02457 
02458   void Update(const ARCONTROLLER_DICTIONARY_ARG_t *arguments, const ::ros::Time& t)
02459   {
02460     if (arguments == NULL)
02461     {
02462       ARSAL_PRINT(ARSAL_PRINT_WARNING, "CB", "CommonRunStateRunIdChanged::Update() arguments is NULL");
02463       return;
02464     }
02465 
02466     ::boost::lock_guard<boost::mutex> lock(mutex_);
02467     msg_ptr.reset(new ::bebop_msgs::CommonRunStateRunIdChanged());
02468     msg_ptr->header.stamp = t;
02469     msg_ptr->header.frame_id = "base_link";
02470 
02471 
02472     arg = NULL;
02473     HASH_FIND_STR (arguments, ARCONTROLLER_DICTIONARY_KEY_COMMON_RUNSTATE_RUNIDCHANGED_RUNID, arg);
02474     if (arg)
02475     {
02476       msg_ptr->runId = arg->value.String;
02477     }
02478 
02479     if (pub_enabled_) ros_pub_.publish(msg_ptr);
02480   }
02481 
02482 };  // CommonRunStateRunIdChanged
02483 
02484 
02485 }  // namespace cb
02486 }  // namespace bebop_driver
02487 #endif  // BEBOP_AUTONOMY_AUTOGENERATED_common_STATE_CALLBACKS_H


bebop_driver
Author(s): Mani Monajjemi
autogenerated on Mon Aug 21 2017 02:36:39