34 #ifndef RC_VISARD_DRIVERNODELET_H 35 #define RC_VISARD_DRIVERNODELET_H 38 #include <dynamic_reconfigure/server.h> 39 #include <rc_visard_driver/rc_visard_driverConfig.h> 40 #include <std_srvs/Trigger.h> 53 #include <rc_visard_driver/GetTrajectory.h> 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);
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);
109 const std::string& frame_id_prefix,
bool tfEnabled);
124 dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>*
reconfig;
138 rc_visard_driver::rc_visard_driverConfig
config;
ThreadedStream::Manager::Ptr dynamicsStreams
std::shared_ptr< RemoteInterface > Ptr
bool autopublishTrajectory
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 'SingleFrame'.
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::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'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
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
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()
int cntConsecutiveRecoveryFails
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
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 tfPrefix
all frame names must be prefixed when using more than one rc_visard
ros::ServiceServer slamRemoveMapService