Public Member Functions | Static Public Attributes | Protected Attributes | Private Member Functions | Private Attributes | List of all members
urcl::DashboardClient Class Reference

This class is a wrapper around the dashboard server. More...

#include <dashboard_client.h>

Inheritance diagram for urcl::DashboardClient:
Inheritance graph
[legend]

Public Member Functions

void assertVersion (const std::string &e_series_min_ver, const std::string &cb3_min_ver, const std::string &required_call)
 Makes sure that the dashboard_server's version is above the required version. More...
 
bool commandAddToLog (const std::string &log_text)
 Send text to log. More...
 
bool commandBrakeRelease ()
 Send Brake release command. More...
 
bool commandClearOperationalMode ()
 Send Clear operational mode command. More...
 
bool commandClosePopup ()
 Send Close popup command. More...
 
bool commandCloseSafetyPopup ()
 Send Close safety popup command. More...
 
bool commandGenerateFlightReport (const std::string &report_type)
 Send Generate flight report command. More...
 
bool commandGenerateSupportFile (const std::string &dir_path)
 Send Generate support file command. More...
 
bool commandGetLoadedProgram (std::string &loaded_program)
 Get Loaded Program. More...
 
bool commandGetOperationalMode (std::string &operational_mode)
 Get Operational mode. More...
 
bool commandGetRobotModel (std::string &robot_model)
 Get Robot model. More...
 
bool commandGetSerialNumber (std::string &serial_number)
 Get Serial number. More...
 
bool commandGetUserRole (std::string &user_role)
 Send Get user role command (Only available for CB3) More...
 
bool commandIsInRemoteControl ()
 Send "Is in remote control" query command. More...
 
bool commandIsProgramSaved ()
 Send "Is program saved" request command. More...
 
bool commandLoadInstallation (const std::string &installation_file_name)
 Send Load installation command. More...
 
bool commandLoadProgram (const std::string &program_file_name)
 Send Load program command. More...
 
bool commandPause ()
 Send Pause program command. More...
 
bool commandPlay ()
 Send Play program command. More...
 
bool commandPolyscopeVersion (std::string &polyscope_version)
 Get Polyscope version. More...
 
bool commandPopup (const std::string &popup_text)
 Send popup command. More...
 
bool commandPowerOff ()
 Send Power off command. More...
 
bool commandPowerOn (const std::chrono::duration< double > timeout=std::chrono::seconds(300))
 Send Power on command. More...
 
bool commandProgramState (std::string &program_state)
 Get Program state. More...
 
bool commandQuit ()
 Send Quit command. More...
 
bool commandRestartSafety ()
 Send Restart Safety command. More...
 
bool commandRobotMode (std::string &robot_mode)
 Get Robot mode. More...
 
bool commandRunning ()
 Send Running command. More...
 
bool commandSafetyMode (std::string &safety_mode)
 Get Safety mode. More...
 
bool commandSafetyStatus (std::string &safety_status)
 Get Safety status. More...
 
bool commandSaveLog ()
 Flush the polyscope log to the log_history.txt file. More...
 
bool commandSetOperationalMode (const std::string &operational_mode)
 Send Set operational mode command (Only available for e-series) More...
 
bool commandSetUserRole (const std::string &user_role)
 Send Set user role command (Only available for CB3) More...
 
bool commandShutdown ()
 Send Shutdown command. More...
 
bool commandStop ()
 Send Stop program command. More...
 
bool commandUnlockProtectiveStop ()
 Send Unlock Protective stop popup command. More...
 
bool connect (const size_t max_num_tries=0, const std::chrono::milliseconds reconnection_time=std::chrono::seconds(10))
 Opens a connection to the dashboard server on the host as specified in the constructor. More...
 
 DashboardClient ()=delete
 
 DashboardClient (const std::string &host)
 Constructor that shall be used by default. More...
 
void disconnect ()
 Makes sure no connection to the dashboard server is held inside the object. More...
 
timeval getConfiguredReceiveTimeout () const
 Gets the configured receive timeout. If receive timeout is unconfigured "normal" socket timeout of 1 second will be returned. More...
 
bool retryCommand (const std::string &requestCommand, const std::string &requestExpectedResponse, const std::string &waitRequest, const std::string &waitExpectedResponse, const std::chrono::duration< double > timeout, const std::chrono::duration< double > retry_period=std::chrono::seconds(1))
 Keep Sending the requesting Command and wait until it returns the expected answer. More...
 
std::string sendAndReceive (const std::string &command)
 Sends a command through the socket and waits for an answer. More...
 
bool sendRequest (const std::string &command, const std::string &expected)
 Sends command and compare it with the expected answer. More...
 
std::string sendRequestString (const std::string &command, const std::string &expected)
 Sends command and compare it with the expected answer. More...
 
bool waitForReply (const std::string &command, const std::string &expected, std::chrono::duration< double > timeout=std::chrono::seconds(30))
 brief Sends a command and wait until it returns the expected answer More...
 
virtual ~DashboardClient ()=default
 
- Public Member Functions inherited from urcl::comm::TCPSocket
void close ()
 Closes the connection to the socket. More...
 
std::string getIP () const
 Determines the local IP address of the currently configured socket. More...
 
socket_t getSocketFD ()
 Getter for the file descriptor of the socket. More...
 
SocketState getState ()
 Getter for the state of the socket. More...
 
bool read (char *character)
 Reads one byte from the socket. More...
 
bool read (uint8_t *buf, const size_t buf_len, size_t &read)
 Reads data from the socket. More...
 
void setReceiveTimeout (const timeval &timeout)
 Setup Receive timeout used for this socket. More...
 
void setReconnectionTime (const std::chrono::milliseconds reconnection_time)
 Set reconnection time, if the server is unavailable during connection this will set the time before trying connect to the server again. More...
 
 TCPSocket ()
 Creates a TCPSocket object. More...
 
bool write (const uint8_t *buf, const size_t buf_len, size_t &written)
 Writes to the socket. More...
 
virtual ~TCPSocket ()
 

Static Public Attributes

static constexpr int DASHBOARD_SERVER_PORT = 29999
 
- Static Public Attributes inherited from urcl::comm::TCPSocket
static constexpr std::chrono::milliseconds DEFAULT_RECONNECTION_TIME { 10000 }
 

Protected Attributes

VersionInformation polyscope_version_
 
- Protected Attributes inherited from urcl::comm::TCPSocket
std::unique_ptr< timeval > recv_timeout_
 

Private Member Functions

std::string read ()
 
void rtrim (std::string &str, const std::string &chars="\t\n\v\f\r ")
 
bool send (const std::string &text)
 

Private Attributes

std::string host_
 
int port_
 
std::mutex write_mutex_
 

Additional Inherited Members

- Protected Member Functions inherited from urcl::comm::TCPSocket
bool setup (const std::string &host, const int port, const size_t max_num_tries=0, const std::chrono::milliseconds reconnection_time=DEFAULT_RECONNECTION_TIME)
 
- Static Protected Member Functions inherited from urcl::comm::TCPSocket
static bool open (socket_t socket_fd, struct sockaddr *address, size_t address_len)
 

Detailed Description

This class is a wrapper around the dashboard server.

For every Dashboard command there exists a wrapper function that will send the request and wait for the server's response.

For documentation about the dashboard server, please see

Definition at line 46 of file dashboard_client.h.

Constructor & Destructor Documentation

◆ DashboardClient() [1/2]

urcl::DashboardClient::DashboardClient ( const std::string &  host)

Constructor that shall be used by default.

Parameters
hostIP address of the robot

Definition at line 45 of file dashboard_client.cpp.

◆ DashboardClient() [2/2]

urcl::DashboardClient::DashboardClient ( )
delete

◆ ~DashboardClient()

virtual urcl::DashboardClient::~DashboardClient ( )
virtualdefault

Member Function Documentation

◆ assertVersion()

void urcl::DashboardClient::assertVersion ( const std::string &  e_series_min_ver,
const std::string &  cb3_min_ver,
const std::string &  required_call 
)

Makes sure that the dashboard_server's version is above the required version.

Parameters
e_series_min_verSW version for e-Series
cb3_min_verSW version for cb3
required_callThe dashboard call that should be checked
Exceptions
UrExceptionif the robot's version isn't large enough

Definition at line 488 of file dashboard_client.cpp.

◆ commandAddToLog()

bool urcl::DashboardClient::commandAddToLog ( const std::string &  log_text)

Send text to log.

Parameters
log_textThe text to be sent to the log
Returns
True succeeded

Definition at line 349 of file dashboard_client.cpp.

◆ commandBrakeRelease()

bool urcl::DashboardClient::commandBrakeRelease ( )

Send Brake release command.

Returns
True succeeded

Definition at line 244 of file dashboard_client.cpp.

◆ commandClearOperationalMode()

bool urcl::DashboardClient::commandClearOperationalMode ( )

Send Clear operational mode command.

Exceptions
anUrException when called on CB3 robots
Returns
True succeeded

Definition at line 436 of file dashboard_client.cpp.

◆ commandClosePopup()

bool urcl::DashboardClient::commandClosePopup ( )

Send Close popup command.

Returns
True succeeded

Definition at line 286 of file dashboard_client.cpp.

◆ commandCloseSafetyPopup()

bool urcl::DashboardClient::commandCloseSafetyPopup ( )

Send Close safety popup command.

Returns
True succeeded

Definition at line 292 of file dashboard_client.cpp.

◆ commandGenerateFlightReport()

bool urcl::DashboardClient::commandGenerateFlightReport ( const std::string &  report_type)

Send Generate flight report command.

Parameters
report_typeThe report type to set for the flight report
Returns
True succeeded

Definition at line 456 of file dashboard_client.cpp.

◆ commandGenerateSupportFile()

bool urcl::DashboardClient::commandGenerateSupportFile ( const std::string &  dir_path)

Send Generate support file command.

Parameters
dir_pathThe path to the directory of an already existing directory location inside the programs directory, where the support file is saved
Returns
True succeeded

Definition at line 469 of file dashboard_client.cpp.

◆ commandGetLoadedProgram()

bool urcl::DashboardClient::commandGetLoadedProgram ( std::string &  loaded_program)

Get Loaded Program.

Parameters
loaded_programThe path to the loaded program
Returns
True succeeded

Definition at line 389 of file dashboard_client.cpp.

◆ commandGetOperationalMode()

bool urcl::DashboardClient::commandGetOperationalMode ( std::string &  operational_mode)

Get Operational mode.

Parameters
operational_modeThe operational mode of the robot returned (Only available for e-series)
Exceptions
anUrException when called on CB3 robots
Returns
True succeeded

Definition at line 421 of file dashboard_client.cpp.

◆ commandGetRobotModel()

bool urcl::DashboardClient::commandGetRobotModel ( std::string &  robot_model)

Get Robot model.

Parameters
robot_modelThe string for the robot model returned
Returns
True succeeded

Definition at line 365 of file dashboard_client.cpp.

◆ commandGetSerialNumber()

bool urcl::DashboardClient::commandGetSerialNumber ( std::string &  serial_number)

Get Serial number.

Parameters
serial_numberThe serial number of the robot returned
Returns
True succeeded

Definition at line 373 of file dashboard_client.cpp.

◆ commandGetUserRole()

bool urcl::DashboardClient::commandGetUserRole ( std::string &  user_role)

Send Get user role command (Only available for CB3)

Parameters
user_roleThe user role on the robot
Exceptions
anUrException when called on e-series robots
Returns
True succeeded

Definition at line 448 of file dashboard_client.cpp.

◆ commandIsInRemoteControl()

bool urcl::DashboardClient::commandIsInRemoteControl ( )

Send "Is in remote control" query command.

Exceptions
anUrException when called on CB3 robots
Returns
True if the robot is currently in remote control

Definition at line 335 of file dashboard_client.cpp.

◆ commandIsProgramSaved()

bool urcl::DashboardClient::commandIsProgramSaved ( )

Send "Is program saved" request command.

Returns
True if the program is saved correctly

Definition at line 329 of file dashboard_client.cpp.

◆ commandLoadInstallation()

bool urcl::DashboardClient::commandLoadInstallation ( const std::string &  installation_file_name)

Send Load installation command.

Parameters
installation_file_nameThe installation file name with the installation extension
Returns
True succeeded

Definition at line 261 of file dashboard_client.cpp.

◆ commandLoadProgram()

bool urcl::DashboardClient::commandLoadProgram ( const std::string &  program_file_name)

Send Load program command.

Parameters
program_file_nameThe urp program file name with the urp extension
Returns
True succeeded

Definition at line 250 of file dashboard_client.cpp.

◆ commandPause()

bool urcl::DashboardClient::commandPause ( )

Send Pause program command.

Returns
True succeeded

Definition at line 274 of file dashboard_client.cpp.

◆ commandPlay()

bool urcl::DashboardClient::commandPlay ( )

Send Play program command.

Returns
True succeeded

Definition at line 268 of file dashboard_client.cpp.

◆ commandPolyscopeVersion()

bool urcl::DashboardClient::commandPolyscopeVersion ( std::string &  polyscope_version)

Get Polyscope version.

Parameters
polyscope_versionThe string for the polyscope version number returned
Returns
True succeeded

Definition at line 355 of file dashboard_client.cpp.

◆ commandPopup()

bool urcl::DashboardClient::commandPopup ( const std::string &  popup_text)

Send popup command.

Parameters
popup_textThe text to be shown in the popup
Returns
True succeeded

Definition at line 343 of file dashboard_client.cpp.

◆ commandPowerOff()

bool urcl::DashboardClient::commandPowerOff ( )

Send Power off command.

Returns
True succeeded

Definition at line 232 of file dashboard_client.cpp.

◆ commandPowerOn()

bool urcl::DashboardClient::commandPowerOn ( const std::chrono::duration< double >  timeout = std::chrono::seconds(300))

Send Power on command.

Parameters
timeoutTimeout in seconds - The robot might take some time to boot before this call can be made successfully.
Returns
True succeeded

Definition at line 238 of file dashboard_client.cpp.

◆ commandProgramState()

bool urcl::DashboardClient::commandProgramState ( std::string &  program_state)

Get Program state.

Parameters
program_stateThe program state of the robot returned
Returns
True succeeded

Definition at line 413 of file dashboard_client.cpp.

◆ commandQuit()

bool urcl::DashboardClient::commandQuit ( )

Send Quit command.

Returns
True succeeded

Definition at line 316 of file dashboard_client.cpp.

◆ commandRestartSafety()

bool urcl::DashboardClient::commandRestartSafety ( )

Send Restart Safety command.

Returns
True succeeded

Definition at line 298 of file dashboard_client.cpp.

◆ commandRobotMode()

bool urcl::DashboardClient::commandRobotMode ( std::string &  robot_mode)

Get Robot mode.

Parameters
robot_modeThe mode of the robot returned
Returns
True succeeded

Definition at line 381 of file dashboard_client.cpp.

◆ commandRunning()

bool urcl::DashboardClient::commandRunning ( )

Send Running command.

Returns
True succeeded

Definition at line 322 of file dashboard_client.cpp.

◆ commandSafetyMode()

bool urcl::DashboardClient::commandSafetyMode ( std::string &  safety_mode)

Get Safety mode.

Parameters
safety_modeThe safety mode of the robot returned
Returns
True succeeded

Definition at line 397 of file dashboard_client.cpp.

◆ commandSafetyStatus()

bool urcl::DashboardClient::commandSafetyStatus ( std::string &  safety_status)

Get Safety status.

Parameters
safety_statusThe safety status of the robot returned
Returns
True succeeded

Definition at line 405 of file dashboard_client.cpp.

◆ commandSaveLog()

bool urcl::DashboardClient::commandSaveLog ( )

Flush the polyscope log to the log_history.txt file.

Returns
True succeeded

Definition at line 482 of file dashboard_client.cpp.

◆ commandSetOperationalMode()

bool urcl::DashboardClient::commandSetOperationalMode ( const std::string &  operational_mode)

Send Set operational mode command (Only available for e-series)

Parameters
operational_modeThe operational mode to set on the robot
Exceptions
anUrException when called on CB3 robots
Returns
True succeeded

Definition at line 429 of file dashboard_client.cpp.

◆ commandSetUserRole()

bool urcl::DashboardClient::commandSetUserRole ( const std::string &  user_role)

Send Set user role command (Only available for CB3)

Parameters
user_roleThe user role to set on the robot
Exceptions
anUrException when called on e-series robots
Returns
True succeeded

Definition at line 442 of file dashboard_client.cpp.

◆ commandShutdown()

bool urcl::DashboardClient::commandShutdown ( )

Send Shutdown command.

Returns
True succeeded

Definition at line 310 of file dashboard_client.cpp.

◆ commandStop()

bool urcl::DashboardClient::commandStop ( )

Send Stop program command.

Returns
True succeeded

Definition at line 280 of file dashboard_client.cpp.

◆ commandUnlockProtectiveStop()

bool urcl::DashboardClient::commandUnlockProtectiveStop ( )

Send Unlock Protective stop popup command.

Returns
True succeeded

Definition at line 304 of file dashboard_client.cpp.

◆ connect()

bool urcl::DashboardClient::connect ( const size_t  max_num_tries = 0,
const std::chrono::milliseconds  reconnection_time = std::chrono::seconds(10) 
)

Opens a connection to the dashboard server on the host as specified in the constructor.

Parameters
max_num_triesMaximum number of connection attempts before counting the connection as failed. Unlimited number of attempts when set to 0.
reconnection_timetime in between connection attempts to the server
Returns
True on successful connection, false otherwise.

Definition at line 54 of file dashboard_client.cpp.

◆ disconnect()

void urcl::DashboardClient::disconnect ( )

Makes sure no connection to the dashboard server is held inside the object.

Definition at line 100 of file dashboard_client.cpp.

◆ getConfiguredReceiveTimeout()

timeval urcl::DashboardClient::getConfiguredReceiveTimeout ( ) const

Gets the configured receive timeout. If receive timeout is unconfigured "normal" socket timeout of 1 second will be returned.

Returns
configured receive timeout

Definition at line 519 of file dashboard_client.cpp.

◆ read()

std::string urcl::DashboardClient::read ( )
private

Definition at line 114 of file dashboard_client.cpp.

◆ retryCommand()

bool urcl::DashboardClient::retryCommand ( const std::string &  requestCommand,
const std::string &  requestExpectedResponse,
const std::string &  waitRequest,
const std::string &  waitExpectedResponse,
const std::chrono::duration< double >  timeout,
const std::chrono::duration< double >  retry_period = std::chrono::seconds(1) 
)

Keep Sending the requesting Command and wait until it returns the expected answer.

Parameters
requestCommandRequest command that will be sent to the server
requestExpectedResponseThe expected reply to the request
waitRequestThe status request
waitExpectedResponseThe expected reply on the status
timeoutTimeout before the command is ultimately considered failed
retry_periodRetries will be done with this period
Returns
True when both the requested command was receive with the expected reply as well as the resulting status also is as expected within the timeout time

Definition at line 213 of file dashboard_client.cpp.

◆ rtrim()

void urcl::DashboardClient::rtrim ( std::string &  str,
const std::string &  chars = "\t\n\v\f\r " 
)
private

Definition at line 49 of file dashboard_client.cpp.

◆ send()

bool urcl::DashboardClient::send ( const std::string &  text)
private

Definition at line 106 of file dashboard_client.cpp.

◆ sendAndReceive()

std::string urcl::DashboardClient::sendAndReceive ( const std::string &  command)

Sends a command through the socket and waits for an answer.

Parameters
commandCommand that will be sent to the server.
Exceptions
UrExceptionif no response was read from the dashboard server
Returns
Answer as received by the server cut off any trailing newlines.

Definition at line 137 of file dashboard_client.cpp.

◆ sendRequest()

bool urcl::DashboardClient::sendRequest ( const std::string &  command,
const std::string &  expected 
)

Sends command and compare it with the expected answer.

Parameters
commandCommand that will be sent to the server.
expectedExpected response as a regex string
Returns
True if the reply to the command is as expected

Definition at line 159 of file dashboard_client.cpp.

◆ sendRequestString()

std::string urcl::DashboardClient::sendRequestString ( const std::string &  command,
const std::string &  expected 
)

Sends command and compare it with the expected answer.

Parameters
commandCommand that will be sent to the server.
expectedExpected response as a regex string
Exceptions
UrExceptionif the received answer does not match the expected one.
Returns
Answer string as received by the server

Definition at line 172 of file dashboard_client.cpp.

◆ waitForReply()

bool urcl::DashboardClient::waitForReply ( const std::string &  command,
const std::string &  expected,
std::chrono::duration< double >  timeout = std::chrono::seconds(30) 
)

brief Sends a command and wait until it returns the expected answer

Parameters
commandCommand that will be sent to the server
expectedExpected replay
timeoutTimeout to wait before the command is considered failed.
Returns
True if the reply was as expected within the timeout time

Definition at line 184 of file dashboard_client.cpp.

Member Data Documentation

◆ DASHBOARD_SERVER_PORT

constexpr int urcl::DashboardClient::DASHBOARD_SERVER_PORT = 29999
staticconstexpr

Definition at line 58 of file dashboard_client.h.

◆ host_

std::string urcl::DashboardClient::host_
private

Definition at line 465 of file dashboard_client.h.

◆ polyscope_version_

VersionInformation urcl::DashboardClient::polyscope_version_
protected

Definition at line 458 of file dashboard_client.h.

◆ port_

int urcl::DashboardClient::port_
private

Definition at line 466 of file dashboard_client.h.

◆ write_mutex_

std::mutex urcl::DashboardClient::write_mutex_
private

Definition at line 467 of file dashboard_client.h.


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


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Mon May 26 2025 02:35:58