Go to the documentation of this file.
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 <rc_common_msgs/Trigger.h>
53 #include <rc_visard_driver/GetTrajectory.h>
74 bool dynamicsStart(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
77 bool dynamicsStartSlam(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
80 bool dynamicsRestart(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
83 bool dynamicsRestartSlam(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
86 bool dynamicsStop(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
89 bool dynamicsStopSlam(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
92 bool dynamicsResetSlam(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
96 rc_visard_driver::GetTrajectory::Response& resp);
99 bool saveSlamMap(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
102 bool loadSlamMap(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
105 bool removeSlamMap(rc_common_msgs::Trigger::Request& req, rc_common_msgs::Trigger::Response& resp);
111 const std::string& frame_id_prefix,
bool tfEnabled,
112 bool staticImu2CamTf);
127 dynamic_reconfigure::Server<rc_visard_driver::rc_visard_driverConfig>*
reconfig;
142 boost::recursive_mutex
mtx;
145 rc_visard_driver::rc_visard_driverConfig
config;
std::atomic_uint_least32_t level
ros::ServiceServer dynamicsRestartService
bool atLeastOnceSuccessfullyStarted
ros::ServiceServer dynamicsStartSlamService
ros::ServiceServer slamSaveMapService
ros::ServiceServer slamRemoveMapService
bool autopublishTrajectory
std::shared_ptr< GenApi::CNodeMapRef > rcgnodemap
bool perform_depth_acquisition_trigger
unsigned int totalImageReceiveTimeouts
boost::recursive_mutex mtx
bool dynamicsResetSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Reset SLAM (keep Stereo INS running)
bool dynamicsStopSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Stop SLAM (keep Stereo INS running)
bool dynamicsRestartSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Restart Stereo INS+SLAM.
bool getSlamTrajectory(rc_visard_driver::GetTrajectory::Request &req, rc_visard_driver::GetTrajectory::Response &resp)
Get the Slam trajectory.
bool dynamicsStop(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Stop Stereo INS(+SLAM if running)
void grab(std::string device, rcg::Device::ACCESS access)
void reconfigure(rc_visard_driver::rc_visard_driverConfig &config, uint32_t level)
ros::ServiceServer slamLoadMapService
bool dev_supports_depth_exposure_adapt_timeout
std::string tfPrefix
all frame names must be prefixed when using more than one rc_visard
std::shared_ptr< ThreadedStream > Ptr
bool removeSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Remove the onboard SLAM map.
ros::ServiceServer dynamicsStopSlamService
std::shared_ptr< RemoteInterface > Ptr
std::thread recoverThread
ros::ServiceServer dynamicsRestartSlamService
diagnostic_updater::Updater updater
diagnostics publishing
bool dev_supports_double_shot
bool saveSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Save the onboard SLAM map.
bool dynamicsStartSlam(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Start Stereo INS+SLAM.
bool dynamicsRestart(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Restart Stereo INS.
ros::ServiceServer getSlamTrajectoryService
int cntConsecutiveRecoveryFails
rc::dynamics::RemoteInterface::Ptr dynamicsInterface
void produce_device_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
rc_visard_driver::rc_visard_driverConfig config
ros::ServiceServer depthAcquisitionTriggerService
wrapper for REST-API calls relating to rc_visard's dynamics interface
std::atomic_bool imageSuccess
ThreadedStream::Manager::Ptr dynamicsStreams
std::string gev_packet_size
tf2_ros::StaticTransformBroadcaster tfStaticBroadcaster
ros::ServiceServer dynamicsResetSlamService
dynamic_reconfigure::Server< rc_visard_driver::rc_visard_driverConfig > * reconfig
ros::ServiceServer dynamicsStartService
unsigned int totalConnectionLosses
std::atomic_bool stopImageThread
bool depthAcquisitionTrigger(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Trigger stereo matching in mode 'SingleFrame'.
void keepAliveAndRecoverFromFails()
bool tfEnabled
should poses published also via tf?
std::atomic_bool imageRequested
bool dev_supports_depth_acquisition_trigger
bool dynamicsStart(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Start Stereo INS.
std::shared_ptr< Manager > Ptr
std::atomic_bool stopRecoverThread
unsigned int totalIncompleteBuffers
unsigned int totalCompleteBuffers
bool loadSlamMap(rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
Load the onboard SLAM map.
static ThreadedStream::Ptr CreateDynamicsStreamOfType(rc::dynamics::RemoteInterface::Ptr rcdIface, const std::string &stream, ros::NodeHandle &nh, const std::string &frame_id_prefix, bool tfEnabled, bool staticImu2CamTf)
void produce_connection_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
void initConfiguration(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, rc_visard_driver::rc_visard_driverConfig &cfg, rcg::Device::ACCESS access)
ros::ServiceServer dynamicsStopService
std::shared_ptr< rcg::Device > rcgdev
ros::Publisher trajPublisher
rc_visard_driver
Author(s): Heiko Hirschmueller
, Christian Emmerich , Felix Ruess
autogenerated on Sun May 15 2022 02:25:43