remote_interface.h
Go to the documentation of this file.
1 /*
2  * This file is part of the rc_dynamics_api package.
3  *
4  * Copyright (c) 2017 Roboception GmbH
5  * All rights reserved
6  *
7  * Author: Christian Emmerich
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright notice,
13  * this list of conditions and the following disclaimer.
14  *
15  * 2. Redistributions in binary form must reproduce the above copyright notice,
16  * this list of conditions and the following disclaimer in the documentation
17  * and/or other materials provided with the distribution.
18  *
19  * 3. Neither the name of the copyright holder nor the names of its contributors
20  * may be used to endorse or promote products derived from this software without
21  * specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
24  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
25  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
26  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
27  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
28  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
29  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
30  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
31  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
32  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef RC_DYNAMICS_API_REMOTEINTERFACE_H
37 #define RC_DYNAMICS_API_REMOTEINTERFACE_H
38 
39 #include <string>
40 #include <list>
41 #include <memory>
42 #include <iostream>
43 #include <chrono>
44 
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"
49 
50 #include "data_receiver.h"
51 #include "net_utils.h"
52 #include "trajectory_time.h"
53 
54 namespace rc
55 {
56 namespace dynamics
57 {
79 class RemoteInterface : public std::enable_shared_from_this<RemoteInterface>
80 {
81 public:
82  using Ptr = std::shared_ptr<RemoteInterface>;
83 
86  struct State
87  {
88  static const std::string IDLE;
89  static const std::string RUNNING;
90  static const std::string FATAL;
91  static const std::string STOPPING;
92  static const std::string WAITING_FOR_INS;
93  static const std::string WAITING_FOR_INS_AND_SLAM;
94  static const std::string WAITING_FOR_SLAM;
95  static const std::string RUNNING_WITH_SLAM;
97  static const std::string UNKNOWN;
98  };
99 
100  struct ReturnCode
101  {
102  int value;
103  std::string message;
104  };
105 
108  class InvalidState : public std::runtime_error
109  {
110  public:
111  explicit InvalidState(std::string encountered_state)
112  : runtime_error("Invalid state encountered: " + encountered_state)
113  {
114  }
115  };
116 
118  class NotAccepted : public std::runtime_error
119  {
120  public:
121  explicit NotAccepted(std::string service_name) : runtime_error("Service call not accepted: " + service_name)
122  {
123  }
124  };
125 
127  class DynamicsNotRunning : public std::runtime_error
128  {
129  public:
130  explicit DynamicsNotRunning(std::string state) : runtime_error("No data received: rc_dynamics is not running but in state: " + state)
131  {
132  }
133  };
134 
136  class TooManyStreamDestinations : public std::runtime_error
137  {
138  public:
139  explicit TooManyStreamDestinations(std::string msg) : runtime_error(msg)
140  {
141  }
142  };
143 
145  class TooManyRequests : public std::runtime_error
146  {
147  public:
148  explicit TooManyRequests(std::string url) : runtime_error("rc_visard returned http error code 429 (too many requests): " + url)
149  {
150  }
151  };
152 
154  class NotAvailable : public std::runtime_error
155  {
156  public:
157  explicit NotAvailable(std::string url) : runtime_error("Requested resource is not available on rc_visard (returned http error code 404): " + url)
158  {
159  }
160  };
161 
168  static Ptr create(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
169 
170  virtual ~RemoteInterface();
171 
176  bool checkSystemReady();
177 
182  std::string getDynamicsState();
183 
188  std::string getSlamState();
189 
194  std::string getStereoInsState();
195 
203  std::string start();
210  std::string startSlam();
217  std::string restart();
218 
225  std::string restartSlam();
226 
232  std::string stop();
233 
240  std::string stopSlam();
241 
248  std::string resetSlam();
249 
255  ReturnCode saveSlamMap(unsigned int timeout_ms = 0);
256 
262  ReturnCode loadSlamMap(unsigned int timeout_ms = 0);
263 
269  ReturnCode removeSlamMap(unsigned int timeout_ms = 0);
270 
275  std::list<std::string> getAvailableStreams();
276 
285  std::string getPbMsgTypeOfStream(const std::string& stream);
286 
296  std::list<std::string> getDestinationsOfStream(const std::string& stream);
297 
305  void addDestinationToStream(const std::string& stream, const std::string& destination);
306 
314  void deleteDestinationFromStream(const std::string& stream, const std::string& destination);
315 
323  void deleteDestinationsFromStream(const std::string& stream, const std::list<std::string>& destinations);
324 
336  roboception::msgs::Trajectory getSlamTrajectory(const TrajectoryTime& start = TrajectoryTime::RelativeToStart(),
338  unsigned int timeout_ms = 0);
339 
347  roboception::msgs::Frame getCam2ImuTransform(unsigned int timeout_ms = 0);
348 
370  DataReceiver::Ptr createReceiverForStream(const std::string& stream, const std::string& dest_interface = "",
371  unsigned int dest_port = 0);
372 
373 protected:
374  static std::map<std::string, RemoteInterface::Ptr> remote_interfaces_;
375 
376  RemoteInterface(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
377 
379  void checkStreamTypeAvailable(const std::string& stream);
381  std::string callDynamicsService(std::string service_name);
382  ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms = 0);
383  std::string getState(const std::string& node);
384 
385  std::string visard_addrs_;
388  std::map<std::string, std::list<std::string>> req_streams_;
389  std::list<std::string> avail_streams_;
390  std::map<std::string, std::string> protobuf_map_;
391  std::string base_url_;
393 };
394 }
395 }
396 
397 #endif // RC_DYNAMICS_API_REMOTEINTERFACE_H
rc::dynamics::RemoteInterface::getDestinationsOfStream
std::list< std::string > getDestinationsOfStream(const std::string &stream)
Returns a list of all destinations registered to the specified rc_dynamics stream.
Definition: remote_interface.cc:552
rc::dynamics::RemoteInterface::State::WAITING_FOR_INS
static const std::string WAITING_FOR_INS
Waiting for IMU data, will proceed to RUNNING.
Definition: remote_interface.h:92
rc::dynamics::RemoteInterface::TooManyRequests
Thrown if a REST API call is rejected because of too many requests.
Definition: remote_interface.h:145
rc::dynamics::RemoteInterface
Simple remote interface to access the dynamic state estimates of an rc_visard device as data streams.
Definition: remote_interface.h:79
rc::dynamics::RemoteInterface::State
An enum mirroring the state-machine states enum in rc_dynamics/dynamicsRos.h.
Definition: remote_interface.h:86
rc::dynamics::RemoteInterface::State::STOPPING
static const std::string STOPPING
Intermediate state while transitioning to IDLE (e.g. from RUNNING)
Definition: remote_interface.h:91
rc::dynamics::RemoteInterface::removeSlamMap
ReturnCode removeSlamMap(unsigned int timeout_ms=0)
Removes the SLAM map on the sensor.
Definition: remote_interface.cc:531
rc::dynamics::RemoteInterface::startSlam
std::string startSlam()
Sets rc_dynamics module to running state.
Definition: remote_interface.cc:431
rc::dynamics::RemoteInterface::ReturnCode
Definition: remote_interface.h:100
rc::dynamics::RemoteInterface::getSlamTrajectory
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.
Definition: remote_interface.cc:737
rc::dynamics::RemoteInterface::stop
std::string stop()
Stops rc_dynamics module.
Definition: remote_interface.cc:435
rc::dynamics::RemoteInterface::getPbMsgTypeOfStream
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...
Definition: remote_interface.cc:546
rc::dynamics::RemoteInterface::remote_interfaces_
static std::map< std::string, RemoteInterface::Ptr > remote_interfaces_
Definition: remote_interface.h:374
rc::dynamics::RemoteInterface::State::FATAL
static const std::string FATAL
An error has occured. May be resolvable by stopping.
Definition: remote_interface.h:90
rc::dynamics::RemoteInterface::cleanUpRequestedStreams
void cleanUpRequestedStreams()
Definition: remote_interface.cc:818
rc::dynamics::RemoteInterface::NotAvailable
Thrown if a REST API call is rejected because of 404; i.e. URL not found.
Definition: remote_interface.h:154
rc::dynamics::RemoteInterface::State::RUNNING_WITH_SLAM
static const std::string RUNNING_WITH_SLAM
Stereo INS and SLAM are running.
Definition: remote_interface.h:96
rc::dynamics::RemoteInterface::~RemoteInterface
virtual ~RemoteInterface()
Definition: remote_interface.cc:253
rc::dynamics::DataReceiver::Ptr
std::shared_ptr< DataReceiver > Ptr
Definition: data_receiver.h:72
rc::dynamics::RemoteInterface::TooManyStreamDestinations
Thrown if too many streams are running already on rc_visard.
Definition: remote_interface.h:136
rc::dynamics::RemoteInterface::State::RUNNING
static const std::string RUNNING
Stereo INS is running.
Definition: remote_interface.h:89
rc::dynamics::RemoteInterface::ReturnCode::value
int value
suceess >= 0, failure < 0
Definition: remote_interface.h:102
rc::dynamics::RemoteInterface::NotAccepted::NotAccepted
NotAccepted(std::string service_name)
Definition: remote_interface.h:121
rc::dynamics::RemoteInterface::getSlamState
std::string getSlamState()
Returns the current state of rc_slam module.
Definition: remote_interface.cc:350
rc::dynamics::RemoteInterface::getStereoInsState
std::string getStereoInsState()
Returns the current state of rc_stereo_ins module.
Definition: remote_interface.cc:355
rc::dynamics::RemoteInterface::base_url_
std::string base_url_
Definition: remote_interface.h:391
rc::dynamics::RemoteInterface::NotAvailable::NotAvailable
NotAvailable(std::string url)
Definition: remote_interface.h:157
rc::dynamics::RemoteInterface::createReceiverForStream
DataReceiver::Ptr createReceiverForStream(const std::string &stream, const std::string &dest_interface="", unsigned int dest_port=0)
Convenience method that automatically.
Definition: remote_interface.cc:772
rc::dynamics::RemoteInterface::req_streams_
std::map< std::string, std::list< std::string > > req_streams_
Definition: remote_interface.h:388
rc::dynamics::RemoteInterface::visard_addrs_
std::string visard_addrs_
Definition: remote_interface.h:385
rc::dynamics::RemoteInterface::loadSlamMap
ReturnCode loadSlamMap(unsigned int timeout_ms=0)
Loads the SLAM map on the sensor.
Definition: remote_interface.cc:527
rc::dynamics::RemoteInterface::Ptr
std::shared_ptr< RemoteInterface > Ptr
Definition: remote_interface.h:82
rc::dynamics::RemoteInterface::getDynamicsState
std::string getDynamicsState()
Returns the current state of rc_dynamics module.
Definition: remote_interface.cc:345
rc::dynamics::RemoteInterface::visard_version_
float visard_version_
rc_visard's firmware version as double, i.e. major.minor, e.g. 1.6
Definition: remote_interface.h:387
rc::dynamics::RemoteInterface::RemoteInterface
RemoteInterface(const std::string &rc_visard_ip, unsigned int requests_timeout=5000)
Definition: remote_interface.cc:239
rc::dynamics::RemoteInterface::getAvailableStreams
std::list< std::string > getAvailableStreams()
Returns a list all available streams on rc_visard.
Definition: remote_interface.cc:536
rc
Definition: data_receiver.h:61
rc::dynamics::RemoteInterface::State::WAITING_FOR_SLAM
static const std::string WAITING_FOR_SLAM
Stereo INS is running, waiting for SLAM data, will proceed to RUNNING_WITH_SLAM.
Definition: remote_interface.h:94
rc::dynamics::RemoteInterface::restart
std::string restart()
Restarts the rc_dynamics module to Stereo INS only mode.
Definition: remote_interface.cc:419
rc::dynamics::RemoteInterface::callDynamicsService
std::string callDynamicsService(std::string service_name)
Common functionality for start(), startSlam(), stop(), ...
Definition: remote_interface.cc:360
rc::dynamics::RemoteInterface::stopSlam
std::string stopSlam()
Stops only the SLAM module (via the rc_dynamics module).
Definition: remote_interface.cc:439
rc::dynamics::RemoteInterface::saveSlamMap
ReturnCode saveSlamMap(unsigned int timeout_ms=0)
Saves the SLAM map on the sensor.
Definition: remote_interface.cc:523
rc::dynamics::RemoteInterface::initialized_
bool initialized_
indicates if remote_interface was initialized properly at least once, see checkSystemReady()
Definition: remote_interface.h:386
rc::dynamics::RemoteInterface::NotAccepted
Thrown if a service call is not accepted.
Definition: remote_interface.h:118
rc::dynamics::RemoteInterface::ReturnCode::message
std::string message
Definition: remote_interface.h:103
rc::dynamics::RemoteInterface::timeout_curl_
int timeout_curl_
Definition: remote_interface.h:392
rc::dynamics::RemoteInterface::restartSlam
std::string restartSlam()
Restarts the rc_dynamics module to SLAM mode.
Definition: remote_interface.cc:423
data_receiver.h
rc::dynamics::RemoteInterface::addDestinationToStream
void addDestinationToStream(const std::string &stream, const std::string &destination)
Adds a destination to a stream, i.e.
Definition: remote_interface.cc:572
rc::dynamics::RemoteInterface::State::IDLE
static const std::string IDLE
Not yet started or stopped.
Definition: remote_interface.h:88
rc::dynamics::RemoteInterface::deleteDestinationFromStream
void deleteDestinationFromStream(const std::string &stream, const std::string &destination)
Deletes a destination from a stream, i.e.
Definition: remote_interface.cc:592
rc::dynamics::RemoteInterface::State::WAITING_FOR_INS_AND_SLAM
static const std::string WAITING_FOR_INS_AND_SLAM
Waiting for IMU data, will proceed to WAITING_FOR_SLAM.
Definition: remote_interface.h:93
trajectory_time.h
rc::dynamics::RemoteInterface::avail_streams_
std::list< std::string > avail_streams_
Definition: remote_interface.h:389
net_utils.h
rc::dynamics::RemoteInterface::checkStreamTypeAvailable
void checkStreamTypeAvailable(const std::string &stream)
Definition: remote_interface.cc:830
rc::dynamics::RemoteInterface::callSlamService
ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms=0)
call slam services which have a return code with value and message
Definition: remote_interface.cc:495
rc::dynamics::RemoteInterface::protobuf_map_
std::map< std::string, std::string > protobuf_map_
Definition: remote_interface.h:390
rc::dynamics::RemoteInterface::deleteDestinationsFromStream
void deleteDestinationsFromStream(const std::string &stream, const std::list< std::string > &destinations)
Deletes given destinations from a stream, i.e.
Definition: remote_interface.cc:611
rc::dynamics::RemoteInterface::TooManyStreamDestinations::TooManyStreamDestinations
TooManyStreamDestinations(std::string msg)
Definition: remote_interface.h:139
rc::dynamics::RemoteInterface::InvalidState
Thrown if the current_state response of the dynamics service does not correspond to those in the Stat...
Definition: remote_interface.h:108
rc::dynamics::RemoteInterface::TooManyRequests::TooManyRequests
TooManyRequests(std::string url)
Definition: remote_interface.h:148
rc::TrajectoryTime
Represents a time stamp to query the trajectory of rcvisard's slam module.
Definition: trajectory_time.h:56
rc::dynamics::RemoteInterface::DynamicsNotRunning
Thrown if rc_dynamics is requested to receive dynamics data but component is not running.
Definition: remote_interface.h:127
rc::TrajectoryTime::RelativeToEnd
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.
Definition: trajectory_time.cc:52
rc::dynamics::RemoteInterface::start
std::string start()
Sets rc_dynamics module to running state.
Definition: remote_interface.cc:427
rc::dynamics::RemoteInterface::resetSlam
std::string resetSlam()
Resets the SLAM module The Stereo INS will keep running, if it is.
Definition: remote_interface.cc:444
rc::dynamics::RemoteInterface::getState
std::string getState(const std::string &node)
Definition: remote_interface.cc:331
rc::dynamics::RemoteInterface::create
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.
Definition: remote_interface.cc:223
rc::dynamics::RemoteInterface::getCam2ImuTransform
roboception::msgs::Frame getCam2ImuTransform(unsigned int timeout_ms=0)
Returns the transformation from camera to IMU coordinate frame.
Definition: remote_interface.cc:761
rc::dynamics::RemoteInterface::State::UNKNOWN
static const std::string UNKNOWN
State of component is unknown, e.g. not yet reported.
Definition: remote_interface.h:97
rc::TrajectoryTime::RelativeToStart
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.
Definition: trajectory_time.cc:47
rc::dynamics::RemoteInterface::DynamicsNotRunning::DynamicsNotRunning
DynamicsNotRunning(std::string state)
Definition: remote_interface.h:130
rc::dynamics::RemoteInterface::checkSystemReady
bool checkSystemReady()
Connects with rc_visard and checks the system state of the rc_visard device.
Definition: remote_interface.cc:279
rc::dynamics::RemoteInterface::InvalidState::InvalidState
InvalidState(std::string encountered_state)
Definition: remote_interface.h:111


rc_dynamics_api
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Endres
autogenerated on Wed Mar 2 2022 00:48:50