device_nodelet.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Heiko Hirschmueller
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #ifndef RC_VISARD_DRIVERNODELET_H
35 #define RC_VISARD_DRIVERNODELET_H
36 
37 #include <nodelet/nodelet.h>
38 #include <dynamic_reconfigure/server.h>
39 #include <rc_visard_driver/rc_visard_driverConfig.h>
40 #include <std_srvs/Trigger.h>
41 
42 #include <GenApi/GenApi.h>
43 #include <rc_genicam_api/device.h>
45 
46 #include <thread>
47 #include <mutex>
48 #include <atomic>
49 
50 #include "protobuf2ros_stream.h"
51 #include "ThreadedStream.h"
52 
53 #include <rc_visard_driver/GetTrajectory.h>
54 
56 
57 namespace rc
58 {
60 {
61 public:
62  DeviceNodelet();
63  virtual ~DeviceNodelet();
64 
65  virtual void onInit();
66 
69  bool depthAcquisitionTrigger(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
72  bool dynamicsStart(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
75  bool dynamicsStartSlam(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
78  bool dynamicsRestart(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
81  bool dynamicsRestartSlam(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
84  bool dynamicsStop(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
87  bool dynamicsStopSlam(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
90  bool dynamicsResetSlam(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
93  bool getSlamTrajectory(rc_visard_driver::GetTrajectory::Request& req,
94  rc_visard_driver::GetTrajectory::Response& resp);
97  bool saveSlamMap(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
100  bool loadSlamMap(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
103  bool removeSlamMap(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
104 
105 
106 private:
108  const std::string& stream, ros::NodeHandle& nh,
109  const std::string& frame_id_prefix, bool tfEnabled);
110 
111  void initConfiguration(const std::shared_ptr<GenApi::CNodeMapRef>& nodemap,
112  rc_visard_driver::rc_visard_driverConfig& cfg, rcg::Device::ACCESS access);
113 
114  void reconfigure(rc_visard_driver::rc_visard_driverConfig& config, uint32_t level);
115 
116  void grab(std::string device, rcg::Device::ACCESS access);
117 
119 
122 
123 
124  dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>* reconfig;
125 
129 
131 
132  std::shared_ptr<rcg::Device> rcgdev;
133  std::shared_ptr<GenApi::CNodeMapRef> rcgnodemap;
134 
135  std::mutex mtx;
138  rc_visard_driver::rc_visard_driverConfig config;
139  std::atomic_uint_least32_t level;
140 
141  std::thread imageThread;
143 
144  std::thread recoverThread;
145  std::atomic_bool stopRecoverThread;
149 
151 
168 
170  std::string tfPrefix;
171 
173  bool tfEnabled;
174 
179 };
180 }
181 
182 #endif
ThreadedStream::Manager::Ptr dynamicsStreams
std::shared_ptr< RemoteInterface > Ptr
unsigned int totalIncompleteBuffers
void reconfigure(rc_visard_driver::rc_visard_driverConfig &config, uint32_t level)
void produce_connection_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool dynamicsRestart(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Restart Stereo INS.
std::shared_ptr< ThreadedStream > Ptr
bool depthAcquisitionTrigger(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Trigger stereo matching in mode &#39;SingleFrame&#39;.
diagnostic_updater::Updater updater
diagnostics publishing
bool getSlamTrajectory(rc_visard_driver::GetTrajectory::Request &req, rc_visard_driver::GetTrajectory::Response &resp)
Get the Slam trajectory.
ros::ServiceServer slamLoadMapService
void grab(std::string device, rcg::Device::ACCESS access)
std::string dev_version
std::shared_ptr< Manager > Ptr
bool dynamicsStartSlam(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Start Stereo INS+SLAM.
void produce_device_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
bool dynamicsStart(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Start Stereo INS.
ros::ServiceServer depthAcquisitionTriggerService
wrapper for REST-API calls relating to rc_visard&#39;s dynamics interface
ros::ServiceServer dynamicsStartSlamService
ros::ServiceServer getSlamTrajectoryService
bool perform_depth_acquisition_trigger
bool tfEnabled
should poses published also via tf?
bool dev_supports_depth_acquisition_trigger
virtual void onInit()
void initConfiguration(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, rc_visard_driver::rc_visard_driverConfig &cfg, rcg::Device::ACCESS access)
static ThreadedStream::Ptr CreateDynamicsStreamOfType(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled)
std::atomic_bool imageSuccess
std::thread imageThread
ros::ServiceServer dynamicsStopSlamService
unsigned int totalImageReceiveTimeouts
ros::ServiceServer dynamicsRestartSlamService
bool dynamicsStopSlam(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Stop SLAM (keep Stereo INS running)
std::atomic_uint_least32_t level
rc_visard_driver::rc_visard_driverConfig config
void keepAliveAndRecoverFromFails()
ros::ServiceServer slamSaveMapService
bool dynamicsRestartSlam(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Restart Stereo INS+SLAM.
ros::ServiceServer dynamicsStopService
std::atomic_bool imageRequested
bool saveSlamMap(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Save the onboard SLAM map.
std::string gev_packet_size
ros::Publisher trajPublisher
bool loadSlamMap(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Load the onboard SLAM map.
std::shared_ptr< rcg::Device > rcgdev
ros::ServiceServer dynamicsStartService
std::atomic_bool stopImageThread
ros::ServiceServer dynamicsRestartService
dynamic_reconfigure::Server< rc_visard_driver::rc_visard_driverConfig > * reconfig
std::atomic_bool stopRecoverThread
rc::dynamics::RemoteInterface::Ptr dynamicsInterface
std::string dev_macaddr
std::string dev_serialno
std::string gev_userid
bool dynamicsStop(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Stop Stereo INS(+SLAM if running)
std::thread recoverThread
unsigned int totalConnectionLosses
bool removeSlamMap(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Remove the onboard SLAM map.
std::shared_ptr< GenApi::CNodeMapRef > rcgnodemap
bool dynamicsResetSlam(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
Reset SLAM (keep Stereo INS running)
ros::ServiceServer dynamicsResetSlamService
std::string dev_ipaddr
virtual ~DeviceNodelet()
std::string tfPrefix
all frame names must be prefixed when using more than one rc_visard
ros::ServiceServer slamRemoveMapService


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Wed Mar 20 2019 07:55:49