Go to the documentation of this file.
36 #ifndef RC_DYNAMICS_API_REMOTEINTERFACE_H
37 #define RC_DYNAMICS_API_REMOTEINTERFACE_H
45 #include "roboception/msgs/frame.pb.h"
46 #include "roboception/msgs/dynamics.pb.h"
47 #include "roboception/msgs/imu.pb.h"
48 #include "roboception/msgs/trajectory.pb.h"
82 using Ptr = std::shared_ptr<RemoteInterface>;
88 static const std::string
IDLE;
112 : runtime_error(
"Invalid state encountered: " + encountered_state)
121 explicit NotAccepted(std::string service_name) : runtime_error(
"Service call not accepted: " + service_name)
130 explicit DynamicsNotRunning(std::string state) : runtime_error(
"No data received: rc_dynamics is not running but in state: " + state)
148 explicit TooManyRequests(std::string url) : runtime_error(
"rc_visard returned http error code 429 (too many requests): " + url)
157 explicit NotAvailable(std::string url) : runtime_error(
"Requested resource is not available on rc_visard (returned http error code 404): " + url)
168 static Ptr create(
const std::string& rc_visard_ip,
unsigned int requests_timeout = 5000);
255 ReturnCode
saveSlamMap(
unsigned int timeout_ms = 0);
262 ReturnCode
loadSlamMap(
unsigned int timeout_ms = 0);
338 unsigned int timeout_ms = 0);
371 unsigned int dest_port = 0);
376 RemoteInterface(
const std::string& rc_visard_ip,
unsigned int requests_timeout = 5000);
383 std::string
getState(
const std::string& node);
397 #endif // RC_DYNAMICS_API_REMOTEINTERFACE_H
std::list< std::string > getDestinationsOfStream(const std::string &stream)
Returns a list of all destinations registered to the specified rc_dynamics stream.
static const std::string WAITING_FOR_INS
Waiting for IMU data, will proceed to RUNNING.
Thrown if a REST API call is rejected because of too many requests.
Simple remote interface to access the dynamic state estimates of an rc_visard device as data streams.
An enum mirroring the state-machine states enum in rc_dynamics/dynamicsRos.h.
static const std::string STOPPING
Intermediate state while transitioning to IDLE (e.g. from RUNNING)
ReturnCode removeSlamMap(unsigned int timeout_ms=0)
Removes the SLAM map on the sensor.
std::string startSlam()
Sets rc_dynamics module to running state.
roboception::msgs::Trajectory getSlamTrajectory(const TrajectoryTime &start=TrajectoryTime::RelativeToStart(), const TrajectoryTime &end=TrajectoryTime::RelativeToEnd(), unsigned int timeout_ms=0)
Returns the Slam trajectory from the sensor.
std::string stop()
Stops rc_dynamics module.
std::string getPbMsgTypeOfStream(const std::string &stream)
Returns the name of the protobuf message class that corresponds to a given data stream and is require...
static std::map< std::string, RemoteInterface::Ptr > remote_interfaces_
static const std::string FATAL
An error has occured. May be resolvable by stopping.
void cleanUpRequestedStreams()
Thrown if a REST API call is rejected because of 404; i.e. URL not found.
static const std::string RUNNING_WITH_SLAM
Stereo INS and SLAM are running.
virtual ~RemoteInterface()
std::shared_ptr< DataReceiver > Ptr
Thrown if too many streams are running already on rc_visard.
static const std::string RUNNING
Stereo INS is running.
int value
suceess >= 0, failure < 0
NotAccepted(std::string service_name)
std::string getSlamState()
Returns the current state of rc_slam module.
std::string getStereoInsState()
Returns the current state of rc_stereo_ins module.
NotAvailable(std::string url)
DataReceiver::Ptr createReceiverForStream(const std::string &stream, const std::string &dest_interface="", unsigned int dest_port=0)
Convenience method that automatically.
std::map< std::string, std::list< std::string > > req_streams_
std::string visard_addrs_
ReturnCode loadSlamMap(unsigned int timeout_ms=0)
Loads the SLAM map on the sensor.
std::shared_ptr< RemoteInterface > Ptr
std::string getDynamicsState()
Returns the current state of rc_dynamics module.
float visard_version_
rc_visard's firmware version as double, i.e. major.minor, e.g. 1.6
RemoteInterface(const std::string &rc_visard_ip, unsigned int requests_timeout=5000)
std::list< std::string > getAvailableStreams()
Returns a list all available streams on rc_visard.
static const std::string WAITING_FOR_SLAM
Stereo INS is running, waiting for SLAM data, will proceed to RUNNING_WITH_SLAM.
std::string restart()
Restarts the rc_dynamics module to Stereo INS only mode.
std::string callDynamicsService(std::string service_name)
Common functionality for start(), startSlam(), stop(), ...
std::string stopSlam()
Stops only the SLAM module (via the rc_dynamics module).
ReturnCode saveSlamMap(unsigned int timeout_ms=0)
Saves the SLAM map on the sensor.
bool initialized_
indicates if remote_interface was initialized properly at least once, see checkSystemReady()
Thrown if a service call is not accepted.
std::string restartSlam()
Restarts the rc_dynamics module to SLAM mode.
void addDestinationToStream(const std::string &stream, const std::string &destination)
Adds a destination to a stream, i.e.
static const std::string IDLE
Not yet started or stopped.
void deleteDestinationFromStream(const std::string &stream, const std::string &destination)
Deletes a destination from a stream, i.e.
static const std::string WAITING_FOR_INS_AND_SLAM
Waiting for IMU data, will proceed to WAITING_FOR_SLAM.
std::list< std::string > avail_streams_
void checkStreamTypeAvailable(const std::string &stream)
ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms=0)
call slam services which have a return code with value and message
std::map< std::string, std::string > protobuf_map_
void deleteDestinationsFromStream(const std::string &stream, const std::list< std::string > &destinations)
Deletes given destinations from a stream, i.e.
TooManyStreamDestinations(std::string msg)
Thrown if the current_state response of the dynamics service does not correspond to those in the Stat...
TooManyRequests(std::string url)
Represents a time stamp to query the trajectory of rcvisard's slam module.
Thrown if rc_dynamics is requested to receive dynamics data but component is not running.
static TrajectoryTime RelativeToEnd(unsigned long sec=0, unsigned long nsec=0)
Creates a time stamp from the given values as an offset from the end point of the trajectory.
std::string start()
Sets rc_dynamics module to running state.
std::string resetSlam()
Resets the SLAM module The Stereo INS will keep running, if it is.
std::string getState(const std::string &node)
static Ptr create(const std::string &rc_visard_ip, unsigned int requests_timeout=5000)
Creates a local instance of rc_visard's remote pose interface.
roboception::msgs::Frame getCam2ImuTransform(unsigned int timeout_ms=0)
Returns the transformation from camera to IMU coordinate frame.
static const std::string UNKNOWN
State of component is unknown, e.g. not yet reported.
static TrajectoryTime RelativeToStart(unsigned long sec=0, unsigned long nsec=0)
Creates a time stamp from the given values as an offset to the start point of the trajectory.
DynamicsNotRunning(std::string state)
bool checkSystemReady()
Connects with rc_visard and checks the system state of the rc_visard device.
InvalidState(std::string encountered_state)
rc_dynamics_api
Author(s): Heiko Hirschmueller
, Christian Emmerich , Felix Endres
autogenerated on Wed Mar 2 2022 00:48:50