Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | List of all members
rc::dynamics::RemoteInterface Class Reference

Simple remote interface to access the dynamic state estimates of an rc_visard device as data streams. More...

#include <remote_interface.h>

Inheritance diagram for rc::dynamics::RemoteInterface:
Inheritance graph
[legend]

Classes

class  DynamicsNotRunning
 Thrown if rc_dynamics is requested to receive dynamics data but component is not running. More...
 
class  InvalidState
 Thrown if the current_state response of the dynamics service does not correspond to those in the State struct. More...
 
class  NotAccepted
 Thrown if a service call is not accepted. More...
 
struct  ReturnCode
 
struct  State
 An enum mirroring the state-machine states enum in rc_dynamics/dynamicsRos.h. More...
 
class  TooManyRequests
 Thrown if a REST API call is rejected because of too many requests. More...
 
class  TooManyStreamDestinations
 Thrown if too many streams are running already on rc_visard. More...
 

Public Types

using Ptr = std::shared_ptr< RemoteInterface >
 

Public Member Functions

void addDestinationToStream (const std::string &stream, const std::string &destination)
 Adds a destination to a stream, i.e. More...
 
bool checkSystemReady ()
 Connects with rc_visard and checks the system state of the rc_visard device. More...
 
DataReceiver::Ptr createReceiverForStream (const std::string &stream, const std::string &dest_interface="", unsigned int dest_port=0)
 Convenience method that automatically. More...
 
void deleteDestinationFromStream (const std::string &stream, const std::string &destination)
 Deletes a destination from a stream, i.e. More...
 
void deleteDestinationsFromStream (const std::string &stream, const std::list< std::string > &destinations)
 Deletes given destinations from a stream, i.e. More...
 
std::list< std::string > getAvailableStreams ()
 Returns a list all available streams on rc_visard. More...
 
std::list< std::string > getDestinationsOfStream (const std::string &stream)
 Returns a list of all destinations registered to the specified rc_dynamics stream. More...
 
std::string getDynamicsState ()
 Returns the current state of rc_dynamics module. More...
 
std::string getPbMsgTypeOfStream (const std::string &stream)
 Returns the name of the protobuf message class that corresponds to a given data stream and is required for de-serializing the respective messages. More...
 
std::string getSlamState ()
 Returns the current state of rc_slam module. More...
 
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. More...
 
std::string getStereoInsState ()
 Returns the current state of rc_stereo_ins module. More...
 
ReturnCode loadSlamMap (unsigned int timeout_ms=0)
 Loads the SLAM map on the sensor. More...
 
ReturnCode removeSlamMap (unsigned int timeout_ms=0)
 Removes the SLAM map on the sensor. More...
 
std::string resetSlam ()
 Resets the SLAM module The Stereo INS will keep running, if it is. More...
 
std::string restart ()
 Restarts the rc_dynamics module to Stereo INS only mode. More...
 
std::string restartSlam ()
 Restarts the rc_dynamics module to SLAM mode. More...
 
ReturnCode saveSlamMap (unsigned int timeout_ms=0)
 Saves the SLAM map on the sensor. More...
 
std::string start ()
 Sets rc_dynamics module to running state. More...
 
std::string startSlam ()
 Sets rc_dynamics module to running state. More...
 
std::string stop ()
 Stops rc_dynamics module. More...
 
std::string stopSlam ()
 Stops only the SLAM module (via the rc_dynamics module). More...
 
virtual ~RemoteInterface ()
 

Static Public Member Functions

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. More...
 

Protected Member Functions

std::string callDynamicsService (std::string service_name)
 Common functionality for start(), startSlam(), stop(), ... More...
 
ReturnCode callSlamService (std::string service_name, unsigned int timeout_ms=0)
 call slam services which have a return code with value and message More...
 
void checkStreamTypeAvailable (const std::string &stream)
 
void cleanUpRequestedStreams ()
 
std::string getState (const std::string &node)
 
 RemoteInterface (const std::string &rc_visard_ip, unsigned int requests_timeout=5000)
 

Protected Attributes

std::list< std::string > avail_streams_
 
std::string base_url_
 
bool initialized_
 indicates if remote_interface was initialized properly at least once, see checkSystemReady() More...
 
std::map< std::string, std::string > protobuf_map_
 
std::map< std::string, std::list< std::string > > req_streams_
 
int timeout_curl_
 
std::string visard_addrs_
 
float visard_version_
 rc_visard's firmware version as double, i.e. major.minor, e.g. 1.6 More...
 

Static Protected Attributes

static std::map< std::string, RemoteInterface::Ptrremote_interfaces_ = map<string, RemoteInterface::Ptr>()
 

Detailed Description

Simple remote interface to access the dynamic state estimates of an rc_visard device as data streams.

It offers methods to

NOTE: For convenience, a RemoteInterface object automatically keeps track of all data stream destinations requested by itself on the rc_visard device, and deletes them again when it is going to be destructed. Therefore, it is highly important that a RemoteInterface is destructed properly. In order to do so it, is recommended to wrap method calls of RemoteInterface objects with try-catch-blocks as they might throw exceptions and therefore avoid proper destruction of the object.

Definition at line 79 of file remote_interface.h.

Member Typedef Documentation

Definition at line 82 of file remote_interface.h.

Constructor & Destructor Documentation

rc::dynamics::RemoteInterface::~RemoteInterface ( )
virtual

Definition at line 238 of file remote_interface.cc.

rc::dynamics::RemoteInterface::RemoteInterface ( const std::string &  rc_visard_ip,
unsigned int  requests_timeout = 5000 
)
protected

Definition at line 224 of file remote_interface.cc.

Member Function Documentation

void rc::dynamics::RemoteInterface::addDestinationToStream ( const std::string &  stream,
const std::string &  destination 
)

Adds a destination to a stream, i.e.

request rc_visard to stream data of the specified type to the given destination.

Parameters
streamstream type, e.g. "pose", "pose_rt" or "dynamics"
destinationstring-represented destination of the data stream, e.g. "192.168.0.1:30000"

Definition at line 548 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::callDynamicsService ( std::string  service_name)
protected

Common functionality for start(), startSlam(), stop(), ...

Definition at line 345 of file remote_interface.cc.

RemoteInterface::ReturnCode rc::dynamics::RemoteInterface::callSlamService ( std::string  service_name,
unsigned int  timeout_ms = 0 
)
protected

call slam services which have a return code with value and message

Definition at line 471 of file remote_interface.cc.

void rc::dynamics::RemoteInterface::checkStreamTypeAvailable ( const std::string &  stream)
protected

Definition at line 761 of file remote_interface.cc.

bool rc::dynamics::RemoteInterface::checkSystemReady ( )

Connects with rc_visard and checks the system state of the rc_visard device.

Returns
true, if system is ready, false otherwise

Definition at line 264 of file remote_interface.cc.

void rc::dynamics::RemoteInterface::cleanUpRequestedStreams ( )
protected

Definition at line 749 of file remote_interface.cc.

RemoteInterface::Ptr rc::dynamics::RemoteInterface::create ( const std::string &  rc_visard_ip,
unsigned int  requests_timeout = 5000 
)
static

Creates a local instance of rc_visard's remote pose interface.

Parameters
rc_visard_iprc_visard's inet address as string, e.g "192.168.0.12"
requests_timeouttimeout in [ms] for doing REST-API calls, which don't have an explicit timeout parameter

Definition at line 208 of file remote_interface.cc.

DataReceiver::Ptr rc::dynamics::RemoteInterface::createReceiverForStream ( const std::string &  stream,
const std::string &  dest_interface = "",
unsigned int  dest_port = 0 
)

Convenience method that automatically.

1) creates a data receiver (including binding socket to a local network interface) 2) adds a destination to the respective stream on rc_visard device 3) waits/checks for the stream being established 4) (removes the destination automatically from rc_visard device if data receiver is no longer used)

Stream can only be established successfully if rc_dynamics module is running on rc_visard, see (re)start(_slam) methods.

If desired interface for receiving is unspecified (or "") this host's network interfaces are scanned to find a suitable IP address among those. Similar, if port number is unspecified (or 0) it will be assigned arbitrarily as available by network interface layer.

Parameters
dest_interfaceempty or one of this hosts network interfaces, e.g. "eth0"
dest_port0 or this hosts port number
Returns
true, if stream could be initialized successfully

Definition at line 703 of file remote_interface.cc.

void rc::dynamics::RemoteInterface::deleteDestinationFromStream ( const std::string &  stream,
const std::string &  destination 
)

Deletes a destination from a stream, i.e.

request rc_visard to stop streaming data of the specified type to the given destination.

Parameters
streamstream type, e.g. "pose", "pose_rt" or "dynamics"
destinationstring-represented destination of the data stream, e.g. "192.168.0.1:30000"

Definition at line 568 of file remote_interface.cc.

void rc::dynamics::RemoteInterface::deleteDestinationsFromStream ( const std::string &  stream,
const std::list< std::string > &  destinations 
)

Deletes given destinations from a stream, i.e.

request rc_visard to stop streaming data of the specified type to the given destinations.

Parameters
streamstream type, e.g. "pose", "pose_rt" or "dynamics"
destinationslist string-represented destination of the data stream, e.g. "192.168.0.1:30000"

Definition at line 587 of file remote_interface.cc.

list< string > rc::dynamics::RemoteInterface::getAvailableStreams ( )

Returns a list all available streams on rc_visard.

Returns

Definition at line 512 of file remote_interface.cc.

list< string > rc::dynamics::RemoteInterface::getDestinationsOfStream ( const std::string &  stream)

Returns a list of all destinations registered to the specified rc_dynamics stream.

Streams here are represented as their destinations using IP address and port number.

Parameters
streama specific rc_dynamics data stream (e.g. "pose" or "dynamics")
Returns
list of destinations of represented as strings, e.g. "192.168.0.1:30000"

Definition at line 528 of file remote_interface.cc.

string rc::dynamics::RemoteInterface::getDynamicsState ( )

Returns the current state of rc_dynamics module.

Returns
the current state.

Definition at line 330 of file remote_interface.cc.

string rc::dynamics::RemoteInterface::getPbMsgTypeOfStream ( const std::string &  stream)

Returns the name of the protobuf message class that corresponds to a given data stream and is required for de-serializing the respective messages.

Parameters
streama specific rc_dynamics data stream (e.g. "pose", "pose_rt" or "dynamics")
Returns
the corresponding protobuf message type as string (e.g. "Frame" or "Dynamics")

Definition at line 522 of file remote_interface.cc.

string rc::dynamics::RemoteInterface::getSlamState ( )

Returns the current state of rc_slam module.

Returns
the current state.

Definition at line 335 of file remote_interface.cc.

roboception::msgs::Trajectory rc::dynamics::RemoteInterface::getSlamTrajectory ( const TrajectoryTime start = TrajectoryTime::RelativeToStart(),
const TrajectoryTime end = TrajectoryTime::RelativeToEnd(),
unsigned int  timeout_ms = 0 
)

Returns the Slam trajectory from the sensor.

Using the start and end arguments only a subsection of the trajectory can be queried. If both are left empy, the full trajectory is returned.

Parameters
startspecifies the start of the returned trajectory subsection (if empty, the trajectory is returned from its very beginning)
endspecifies the end of the returned trajectory subsection (if empty, the trajectory is included up to its very end)

Definition at line 679 of file remote_interface.cc.

string rc::dynamics::RemoteInterface::getState ( const std::string &  node)
protected

Definition at line 316 of file remote_interface.cc.

string rc::dynamics::RemoteInterface::getStereoInsState ( )

Returns the current state of rc_stereo_ins module.

Returns
the current state.

Definition at line 340 of file remote_interface.cc.

RemoteInterface::ReturnCode rc::dynamics::RemoteInterface::loadSlamMap ( unsigned int  timeout_ms = 0)

Loads the SLAM map on the sensor.

Parameters
timeout_mstimeout in ms for the call (default 0: no timeout)
Returns
return code indicating success and string message

Definition at line 503 of file remote_interface.cc.

RemoteInterface::ReturnCode rc::dynamics::RemoteInterface::removeSlamMap ( unsigned int  timeout_ms = 0)

Removes the SLAM map on the sensor.

Parameters
timeout_mstimeout in ms for the call (default 0: no timeout)
Returns
return code indicating success and string message

Definition at line 507 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::resetSlam ( )

Resets the SLAM module The Stereo INS will keep running, if it is.

Returns
the entered state (of the SLAM module). Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 420 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::restart ( )

Restarts the rc_dynamics module to Stereo INS only mode.

Equivalent to stop() and start()

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 395 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::restartSlam ( )

Restarts the rc_dynamics module to SLAM mode.

Equivalent to stop() and startSlam()

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 399 of file remote_interface.cc.

RemoteInterface::ReturnCode rc::dynamics::RemoteInterface::saveSlamMap ( unsigned int  timeout_ms = 0)

Saves the SLAM map on the sensor.

Parameters
timeout_mstimeout in ms for the call (default 0: no timeout)
Returns
return code indicating success and string message

Definition at line 499 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::start ( )

Sets rc_dynamics module to running state.

Only start the Stereo INS. To start SLAM use startSlam(). To restart use the restart() method.

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 403 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::startSlam ( )

Sets rc_dynamics module to running state.

Also starts up the Stereo INS, if not already running.

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 407 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::stop ( )

Stops rc_dynamics module.

If SLAM is running it will be stopped too.

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 411 of file remote_interface.cc.

std::string rc::dynamics::RemoteInterface::stopSlam ( )

Stops only the SLAM module (via the rc_dynamics module).

The Stereo INS will keep running.

Returns
the entered state. Note that this can be an intermediate state.
Exceptions
InvalidStateif the entered state does not match the known states in State

Definition at line 415 of file remote_interface.cc.

Member Data Documentation

std::list<std::string> rc::dynamics::RemoteInterface::avail_streams_
protected

Definition at line 370 of file remote_interface.h.

std::string rc::dynamics::RemoteInterface::base_url_
protected

Definition at line 372 of file remote_interface.h.

bool rc::dynamics::RemoteInterface::initialized_
protected

indicates if remote_interface was initialized properly at least once, see checkSystemReady()

Definition at line 367 of file remote_interface.h.

std::map<std::string, std::string> rc::dynamics::RemoteInterface::protobuf_map_
protected

Definition at line 371 of file remote_interface.h.

map< string, RemoteInterface::Ptr > rc::dynamics::RemoteInterface::remote_interfaces_ = map<string, RemoteInterface::Ptr>()
staticprotected

Definition at line 355 of file remote_interface.h.

std::map<std::string, std::list<std::string> > rc::dynamics::RemoteInterface::req_streams_
protected

Definition at line 369 of file remote_interface.h.

int rc::dynamics::RemoteInterface::timeout_curl_
protected

Definition at line 373 of file remote_interface.h.

std::string rc::dynamics::RemoteInterface::visard_addrs_
protected

Definition at line 366 of file remote_interface.h.

float rc::dynamics::RemoteInterface::visard_version_
protected

rc_visard's firmware version as double, i.e. major.minor, e.g. 1.6

Definition at line 368 of file remote_interface.h.


The documentation for this class was generated from the following files:


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