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 WAITING_FOR_INS;
92  static const std::string WAITING_FOR_INS_AND_SLAM;
93  static const std::string WAITING_FOR_SLAM;
94  static const std::string RUNNING_WITH_SLAM;
96  static const std::string UNKNOWN;
97  };
98 
99  struct ReturnCode
100  {
101  int value;
102  std::string message;
103  };
104 
107  class InvalidState : public std::runtime_error
108  {
109  public:
110  explicit InvalidState(std::string encountered_state)
111  : runtime_error("Invalid state encountered: " + encountered_state)
112  {
113  }
114  };
115 
117  class NotAccepted : public std::runtime_error
118  {
119  public:
120  explicit NotAccepted(std::string service_name) : runtime_error("Service call not accepted: " + service_name)
121  {
122  }
123  };
124 
126  class DynamicsNotRunning : public std::runtime_error
127  {
128  public:
129  explicit DynamicsNotRunning(std::string state) : runtime_error("No data received: rc_dynamics is not running but in state: " + state)
130  {
131  }
132  };
133 
135  class TooManyStreamDestinations : public std::runtime_error
136  {
137  public:
138  explicit TooManyStreamDestinations(std::string msg) : runtime_error(msg)
139  {
140  }
141  };
142 
144  class TooManyRequests : public std::runtime_error
145  {
146  public:
147  explicit TooManyRequests(std::string url) : runtime_error("rc_visard returned http error code 429 (too many requests): " + url)
148  {
149  }
150  };
151 
158  static Ptr create(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
159 
160  virtual ~RemoteInterface();
161 
166  bool checkSystemReady();
167 
172  std::string getDynamicsState();
173 
178  std::string getSlamState();
179 
184  std::string getStereoInsState();
185 
193  std::string start();
200  std::string startSlam();
207  std::string restart();
208 
215  std::string restartSlam();
216 
222  std::string stop();
223 
230  std::string stopSlam();
231 
238  std::string resetSlam();
239 
245  ReturnCode saveSlamMap(unsigned int timeout_ms = 0);
246 
252  ReturnCode loadSlamMap(unsigned int timeout_ms = 0);
253 
259  ReturnCode removeSlamMap(unsigned int timeout_ms = 0);
260 
265  std::list<std::string> getAvailableStreams();
266 
275  std::string getPbMsgTypeOfStream(const std::string& stream);
276 
286  std::list<std::string> getDestinationsOfStream(const std::string& stream);
287 
295  void addDestinationToStream(const std::string& stream, const std::string& destination);
296 
304  void deleteDestinationFromStream(const std::string& stream, const std::string& destination);
305 
313  void deleteDestinationsFromStream(const std::string& stream, const std::list<std::string>& destinations);
314 
326  roboception::msgs::Trajectory getSlamTrajectory(const TrajectoryTime& start = TrajectoryTime::RelativeToStart(),
328  unsigned int timeout_ms = 0);
329 
351  DataReceiver::Ptr createReceiverForStream(const std::string& stream, const std::string& dest_interface = "",
352  unsigned int dest_port = 0);
353 
354 protected:
355  static std::map<std::string, RemoteInterface::Ptr> remote_interfaces_;
356 
357  RemoteInterface(const std::string& rc_visard_ip, unsigned int requests_timeout = 5000);
358 
360  void checkStreamTypeAvailable(const std::string& stream);
362  std::string callDynamicsService(std::string service_name);
363  ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms = 0);
364  std::string getState(const std::string& node);
365 
366  std::string visard_addrs_;
369  std::map<std::string, std::list<std::string>> req_streams_;
370  std::list<std::string> avail_streams_;
371  std::map<std::string, std::string> protobuf_map_;
372  std::string base_url_;
374 };
375 }
376 }
377 
378 #endif // RC_DYNAMICS_API_REMOTEINTERFACE_H
Simple remote interface to access the dynamic state estimates of an rc_visard device as data streams...
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&#39;s remote pose interface.
std::map< std::string, std::list< std::string > > req_streams_
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::shared_ptr< RemoteInterface > Ptr
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...
float visard_version_
rc_visard&#39;s firmware version as double, i.e. major.minor, e.g. 1.6
void checkStreamTypeAvailable(const std::string &stream)
void deleteDestinationsFromStream(const std::string &stream, const std::list< std::string > &destinations)
Deletes given destinations from a stream, i.e.
std::shared_ptr< DataReceiver > Ptr
Definition: data_receiver.h:72
std::list< std::string > getDestinationsOfStream(const std::string &stream)
Returns a list of all destinations registered to the specified rc_dynamics stream.
Thrown if rc_dynamics is requested to receive dynamics data but component is not running.
std::string resetSlam()
Resets the SLAM module The Stereo INS will keep running, if it is.
std::string getStereoInsState()
Returns the current state of rc_stereo_ins module.
static const std::string RUNNING_WITH_SLAM
Stereo INS and SLAM are running.
DataReceiver::Ptr createReceiverForStream(const std::string &stream, const std::string &dest_interface="", unsigned int dest_port=0)
Convenience method that automatically.
bool initialized_
indicates if remote_interface was initialized properly at least once, see checkSystemReady() ...
static const std::string WAITING_FOR_INS_AND_SLAM
Waiting for IMU data, will proceed to WAITING_FOR_SLAM.
Thrown if a service call is not accepted.
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 std::map< std::string, RemoteInterface::Ptr > remote_interfaces_
bool checkSystemReady()
Connects with rc_visard and checks the system state of the rc_visard device.
std::string restart()
Restarts the rc_dynamics module to Stereo INS only mode.
static const std::string FATAL
An error has occured. May be resolvable by stopping.
void deleteDestinationFromStream(const std::string &stream, const std::string &destination)
Deletes a destination from a stream, i.e.
ReturnCode removeSlamMap(unsigned int timeout_ms=0)
Removes the SLAM map on the sensor.
static const std::string WAITING_FOR_INS
Waiting for IMU data, will proceed to RUNNING.
Thrown if the current_state response of the dynamics service does not correspond to those in the Stat...
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.
std::string stopSlam()
Stops only the SLAM module (via the rc_dynamics module).
Thrown if too many streams are running already on rc_visard.
std::string getSlamState()
Returns the current state of rc_slam module.
Thrown if a REST API call is rejected because of too many requests.
ReturnCode callSlamService(std::string service_name, unsigned int timeout_ms=0)
call slam services which have a return code with value and message
ReturnCode saveSlamMap(unsigned int timeout_ms=0)
Saves the SLAM map on the sensor.
ReturnCode loadSlamMap(unsigned int timeout_ms=0)
Loads the SLAM map on the sensor.
std::string getDynamicsState()
Returns the current state of rc_dynamics module.
InvalidState(std::string encountered_state)
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...
static const std::string IDLE
Not yet started or stopped.
int value
suceess >= 0, failure < 0
An enum mirroring the state-machine states enum in rc_dynamics/dynamicsRos.h.
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...
std::string callDynamicsService(std::string service_name)
Common functionality for start(), startSlam(), stop(), ...
static const std::string UNKNOWN
State of component is unknown, e.g. not yet reported.
std::string startSlam()
Sets rc_dynamics module to running state.
static const std::string RUNNING
Stereo INS is running.
std::list< std::string > avail_streams_
static const std::string WAITING_FOR_SLAM
Stereo INS is running, waiting for SLAM data, will proceed to RUNNING_WITH_SLAM.
std::map< std::string, std::string > protobuf_map_
Represents a time stamp to query the trajectory of rcvisard&#39;s slam module.
std::string start()
Sets rc_dynamics module to running state.


rc_dynamics_api
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Endres
autogenerated on Thu May 9 2019 02:51:36