Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef RC_VISARD_DRIVERNODELET_H
00035 #define RC_VISARD_DRIVERNODELET_H
00036
00037 #include <nodelet/nodelet.h>
00038 #include <dynamic_reconfigure/server.h>
00039 #include <rc_visard_driver/rc_visard_driverConfig.h>
00040 #include <std_srvs/Trigger.h>
00041
00042 #include <GenApi/GenApi.h>
00043 #include <rc_genicam_api/device.h>
00044 #include <rc_dynamics_api/remote_interface.h>
00045
00046 #include <thread>
00047 #include <mutex>
00048 #include <atomic>
00049
00050 #include "protobuf2ros_stream.h"
00051 #include "ThreadedStream.h"
00052
00053
00054 namespace rc
00055 {
00056
00057 class DeviceNodelet : public nodelet::Nodelet
00058 {
00059 public:
00060
00061 DeviceNodelet();
00062 virtual ~DeviceNodelet();
00063
00064 virtual void onInit();
00065
00066 bool startDynamics(std_srvs::Trigger::Request &req,
00067 std_srvs::Trigger::Response &resp);
00068 bool restartDynamics(std_srvs::Trigger::Request &req,
00069 std_srvs::Trigger::Response &resp);
00070 bool stopDynamics(std_srvs::Trigger::Request &req,
00071 std_srvs::Trigger::Response &resp);
00072
00073 private:
00074
00075 static ThreadedStream::Ptr CreateDynamicsStreamOfType(
00076 rc::dynamics::RemoteInterface::Ptr rcdIface,
00077 const std::string &stream, ros::NodeHandle &nh,
00078 const std::string &frame_id_prefix, bool tfEnabled);
00079
00080 void initConfiguration(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
00081 rc_visard_driver::rc_visard_driverConfig &cfg, rcg::Device::ACCESS access);
00082
00083 void reconfigure(rc_visard_driver::rc_visard_driverConfig &config, uint32_t level);
00084
00085 void grab(std::string device, rcg::Device::ACCESS access);
00086
00087 void keepAliveAndRecoverFromFails();
00088
00089 dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig> *reconfig;
00090
00091 bool dev_supports_gain;
00092 bool dev_supports_wb;
00093
00094 std::shared_ptr<rcg::Device> rcgdev;
00095 std::shared_ptr<GenApi::CNodeMapRef> rcgnodemap;
00096
00097 std::mutex mtx;
00098 rc_visard_driver::rc_visard_driverConfig config;
00099 std::atomic_uint_least32_t level;
00100
00101 std::thread imageThread;
00102 std::atomic_bool stopImageThread, imageRequested, imageSuccess;
00103
00104 std::thread recoverThread;
00105 std::atomic_bool stopRecoverThread;
00106 bool recoveryRequested;
00107 int cntConsecutiveRecoveryFails;
00108
00109 ThreadedStream::Manager::Ptr dynamicsStreams;
00110
00112 rc::dynamics::RemoteInterface::Ptr dynamicsInterface;
00113 ros::ServiceServer dynamicsStartService;
00114 ros::ServiceServer dynamicsRestartService;
00115 ros::ServiceServer dynamicsStopService;
00116 bool autostartDynamics, autostopDynamics;
00117
00119 std::string tfPrefix;
00120
00122 bool tfEnabled;
00123 };
00124
00125 }
00126
00127 #endif