Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef RC_DYNAMICS_API_REMOTEINTERFACE_H
00037 #define RC_DYNAMICS_API_REMOTEINTERFACE_H
00038
00039 #include <string>
00040 #include <list>
00041 #include <memory>
00042 #include <iostream>
00043 #include <chrono>
00044
00045 #include "roboception/msgs/frame.pb.h"
00046 #include "roboception/msgs/dynamics.pb.h"
00047 #include "roboception/msgs/imu.pb.h"
00048 #include "roboception/msgs/trajectory.pb.h"
00049
00050 #include "data_receiver.h"
00051 #include "net_utils.h"
00052 #include "trajectory_time.h"
00053
00054 namespace rc
00055 {
00056 namespace dynamics
00057 {
00079 class RemoteInterface : public std::enable_shared_from_this<RemoteInterface>
00080 {
00081 public:
00082 using Ptr = std::shared_ptr<RemoteInterface>;
00083
00086 struct State
00087 {
00088 static const std::string IDLE;
00089 static const std::string RUNNING;
00090 static const std::string FATAL;
00091 static const std::string WAITING_FOR_INS;
00092 static const std::string WAITING_FOR_INS_AND_SLAM;
00093 static const std::string WAITING_FOR_SLAM;
00094
00095 static const std::string RUNNING_WITH_SLAM;
00096 static const std::string UNKNOWN;
00097 };
00098
00099 struct ReturnCode
00100 {
00101 int value;
00102 std::string message;
00103 };
00104
00107 class InvalidState : public std::runtime_error
00108 {
00109 public:
00110 explicit InvalidState(std::string encountered_state)
00111 : runtime_error("Invalid state encountered: " + encountered_state)
00112 {
00113 }
00114 };
00115
00117 class NotAccepted : public std::runtime_error
00118 {
00119 public:
00120 explicit NotAccepted(std::string service_name) : runtime_error("Service call not accepted: " + service_name)
00121 {
00122 }
00123 };
00124
00126 class DynamicsNotRunning : public std::runtime_error
00127 {
00128 public:
00129 explicit DynamicsNotRunning(std::string state) : runtime_error("No data received: rc_dynamics is not running but in state: " + state)
00130 {
00131 }
00132 };
00133
00135 class TooManyStreamDestinations : public std::runtime_error
00136 {
00137 public:
00138 explicit TooManyStreamDestinations(std::string msg) : runtime_error(msg)
00139 {
00140 }
00141 };
00142
00144 class TooManyRequests : public std::runtime_error
00145 {
00146 public:
00147 explicit TooManyRequests(std::string url) : runtime_error("rc_visard returned http error code 429 (too many requests): " + url)
00148 {
00149 }
00150 };
00151
00158 static Ptr create(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
00159
00160 virtual ~RemoteInterface();
00161
00166 bool checkSystemReady();
00167
00172 std::string getDynamicsState();
00173
00178 std::string getSlamState();
00179
00184 std::string getStereoInsState();
00185
00193 std::string start();
00200 std::string startSlam();
00207 std::string restart();
00208
00215 std::string restartSlam();
00216
00222 std::string stop();
00223
00230 std::string stopSlam();
00231
00238 std::string resetSlam();
00239
00245 ReturnCode saveSlamMap(unsigned int timeout_ms = 0);
00246
00252 ReturnCode loadSlamMap(unsigned int timeout_ms = 0);
00253
00259 ReturnCode removeSlamMap(unsigned int timeout_ms = 0);
00260
00265 std::list<std::string> getAvailableStreams();
00266
00275 std::string getPbMsgTypeOfStream(const std::string& stream);
00276
00286 std::list<std::string> getDestinationsOfStream(const std::string& stream);
00287
00295 void addDestinationToStream(const std::string& stream, const std::string& destination);
00296
00304 void deleteDestinationFromStream(const std::string& stream, const std::string& destination);
00305
00313 void deleteDestinationsFromStream(const std::string& stream, const std::list<std::string>& destinations);
00314
00326 roboception::msgs::Trajectory getSlamTrajectory(const TrajectoryTime& start = TrajectoryTime::RelativeToStart(),
00327 const TrajectoryTime& end = TrajectoryTime::RelativeToEnd(),
00328 unsigned int timeout_ms = 0);
00329
00351 DataReceiver::Ptr createReceiverForStream(const std::string& stream, const std::string& dest_interface = "",
00352 unsigned int dest_port = 0);
00353
00354 protected:
00355 static std::map<std::string, RemoteInterface::Ptr> remote_interfaces_;
00356
00357 RemoteInterface(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
00358
00359 void cleanUpRequestedStreams();
00360 void checkStreamTypeAvailable(const std::string& stream);
00362 std::string callDynamicsService(std::string service_name);
00363 ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms = 0);
00364 std::string getState(const std::string& node);
00365
00366 std::string visard_addrs_;
00367 bool initialized_;
00368 float visard_version_;
00369 std::map<std::string, std::list<std::string>> req_streams_;
00370 std::list<std::string> avail_streams_;
00371 std::map<std::string, std::string> protobuf_map_;
00372 std::string base_url_;
00373 int timeout_curl_;
00374 };
00375 }
00376 }
00377
00378 #endif // RC_DYNAMICS_API_REMOTEINTERFACE_H