Functions
ServiceFunctions Namespace Reference

Contains all service functions and their respective implementations. More...

Functions

bool deleteGroup (pses_ucbridge::DeleteGroup::Request &req, pses_ucbridge::DeleteGroup::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to delete a certain group. More...
 
bool getControllerID (pses_ucbridge::GetControllerID::Request &req, pses_ucbridge::GetControllerID::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit its id. More...
 
bool getDAQStatus (pses_ucbridge::GetDAQStatus::Request &req, pses_ucbridge::GetDAQStatus::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the daq status. More...
 
bool getFirmwareVersion (pses_ucbridge::GetFirmwareVersion::Request &req, pses_ucbridge::GetFirmwareVersion::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit its firmware version. More...
 
bool getIMUInfo (pses_ucbridge::GetIMUInfo::Request &req, pses_ucbridge::GetIMUInfo::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the calibration of its IMU. More...
 
bool getInfoAllGroups (pses_ucbridge::GetInfoAllGroups::Request &req, pses_ucbridge::GetInfoAllGroups::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit info about all registered groups. More...
 
bool getInfoGroup (pses_ucbridge::GetInfoGroup::Request &req, pses_ucbridge::GetInfoGroup::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the info about a particular group. More...
 
bool getKinectStatus (pses_ucbridge::GetKinectStatus::Request &req, pses_ucbridge::GetKinectStatus::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the power supply status of the kinect. More...
 
bool getMagASA (pses_ucbridge::GetMagASA::Request &req, pses_ucbridge::GetMagASA::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the calibration of its magnetic field sensor. More...
 
bool getMagInfo (pses_ucbridge::GetMagInfo::Request &req, pses_ucbridge::GetMagInfo::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit info about its magnetic field sensor. More...
 
bool getMotorLevel (pses_ucbridge::GetMotorLevel::Request &req, pses_ucbridge::GetMotorLevel::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the current motor level. More...
 
bool getSessionID (pses_ucbridge::GetSessionID::Request &req, pses_ucbridge::GetSessionID::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit its current session id. More...
 
bool getSteeringLevel (pses_ucbridge::GetSteeringLevel::Request &req, pses_ucbridge::GetSteeringLevel::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the current steering level. More...
 
bool getUSInfo (pses_ucbridge::GetUSInfo::Request &req, pses_ucbridge::GetUSInfo::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to transmit the calibration of its ultra sonic range sensors. More...
 
bool resetController (pses_ucbridge::ResetController::Request &req, pses_ucbridge::ResetController::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to do perform a soft reset. More...
 
bool resetDMS (pses_ucbridge::ResetDMS::Request &req, pses_ucbridge::ResetDMS::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to reset the counter on the dead man's switch. More...
 
bool setIMU (pses_ucbridge::SetIMU::Request &req, pses_ucbridge::SetIMU::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to change the calibration of its IMU. More...
 
bool setMag (pses_ucbridge::SetMag::Request &req, pses_ucbridge::SetMag::Response &res, Communication *com)
 A call to this Service will send a command to the serial device whether to use the magnetic field sensor calibration or not. More...
 
bool setMotorLevel (pses_ucbridge::SetMotorLevel::Request &req, pses_ucbridge::SetMotorLevel::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to change the current motor level. More...
 
bool setSessionID (pses_ucbridge::SetSessionID::Request &req, pses_ucbridge::SetSessionID::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to set the current session id. More...
 
bool setSteeringLevel (pses_ucbridge::SetSteering::Request &req, pses_ucbridge::SetSteering::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to change the current steering level. More...
 
bool setUS (pses_ucbridge::SetUS::Request &req, pses_ucbridge::SetUS::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to change the calibration of its ultra sonic range sensors. More...
 
bool toggleBrakes (pses_ucbridge::ToggleBrakes::Request &req, pses_ucbridge::ToggleBrakes::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate its motor brakes. More...
 
bool toggleDAQ (pses_ucbridge::ToggleDAQ::Request &req, pses_ucbridge::ToggleDAQ::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate the daq. More...
 
bool toggleDMS (pses_ucbridge::ToggleDMS::Request &req, pses_ucbridge::ToggleDMS::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate the dead man's switch. More...
 
bool toggleGroup (pses_ucbridge::ToggleGroup::Request &req, pses_ucbridge::ToggleGroup::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate a particular group. More...
 
bool toggleKinect (pses_ucbridge::ToggleKinect::Request &req, pses_ucbridge::ToggleKinect::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate the kinect power supply. More...
 
bool toggleMotor (pses_ucbridge::ToggleMotor::Request &req, pses_ucbridge::ToggleMotor::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate the motor controller. More...
 
bool toggleUS (pses_ucbridge::ToggleUS::Request &req, pses_ucbridge::ToggleUS::Response &res, Communication *com)
 A call to this Service will send a command to the serial device to activate/deactivate the ultra sonic range sensors. More...
 

Detailed Description

Contains all service functions and their respective implementations.

Service functions get called whenever a ROS node calls a Service.

Function Documentation

bool ServiceFunctions::deleteGroup ( pses_ucbridge::DeleteGroup::Request &  req,
pses_ucbridge::DeleteGroup::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to delete a certain group.

Parameters
[in]reqRequest message defines which group should be deleted.
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 63 of file servicefunctions.h.

bool ServiceFunctions::getControllerID ( pses_ucbridge::GetControllerID::Request &  req,
pses_ucbridge::GetControllerID::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit its id.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested id.
Returns
true is no errors occured, else false.

Definition at line 93 of file servicefunctions.h.

bool ServiceFunctions::getDAQStatus ( pses_ucbridge::GetDAQStatus::Request &  req,
pses_ucbridge::GetDAQStatus::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the daq status.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested daq status.
Returns
true is no errors occured, else false.

Definition at line 126 of file servicefunctions.h.

bool ServiceFunctions::getFirmwareVersion ( pses_ucbridge::GetFirmwareVersion::Request &  req,
pses_ucbridge::GetFirmwareVersion::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit its firmware version.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested firmware version.
Returns
true is no errors occured, else false.

Definition at line 159 of file servicefunctions.h.

bool ServiceFunctions::getIMUInfo ( pses_ucbridge::GetIMUInfo::Request &  req,
pses_ucbridge::GetIMUInfo::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the calibration of its IMU.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested IMU info.
Returns
true is no errors occured, else false.

Definition at line 192 of file servicefunctions.h.

bool ServiceFunctions::getInfoAllGroups ( pses_ucbridge::GetInfoAllGroups::Request &  req,
pses_ucbridge::GetInfoAllGroups::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit info about all registered groups.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested group info.
Returns
true is no errors occured, else false.

Definition at line 224 of file servicefunctions.h.

bool ServiceFunctions::getInfoGroup ( pses_ucbridge::GetInfoGroup::Request &  req,
pses_ucbridge::GetInfoGroup::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the info about a particular group.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested group info.
Returns
true is no errors occured, else false.

Definition at line 257 of file servicefunctions.h.

bool ServiceFunctions::getKinectStatus ( pses_ucbridge::GetKinectStatus::Request &  req,
pses_ucbridge::GetKinectStatus::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the power supply status of the kinect.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested kinect status.
Returns
true is no errors occured, else false.

Definition at line 290 of file servicefunctions.h.

bool ServiceFunctions::getMagASA ( pses_ucbridge::GetMagASA::Request &  req,
pses_ucbridge::GetMagASA::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the calibration of its magnetic field sensor.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested Mag info.
Returns
true is no errors occured, else false.

Definition at line 323 of file servicefunctions.h.

bool ServiceFunctions::getMagInfo ( pses_ucbridge::GetMagInfo::Request &  req,
pses_ucbridge::GetMagInfo::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit info about its magnetic field sensor.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested Mag info.
Returns
true is no errors occured, else false.

Definition at line 356 of file servicefunctions.h.

bool ServiceFunctions::getMotorLevel ( pses_ucbridge::GetMotorLevel::Request &  req,
pses_ucbridge::GetMotorLevel::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the current motor level.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested motor level info.
Returns
true is no errors occured, else false.

Definition at line 388 of file servicefunctions.h.

bool ServiceFunctions::getSessionID ( pses_ucbridge::GetSessionID::Request &  req,
pses_ucbridge::GetSessionID::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit its current session id.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested session id.
Returns
true is no errors occured, else false.

Definition at line 429 of file servicefunctions.h.

bool ServiceFunctions::getSteeringLevel ( pses_ucbridge::GetSteeringLevel::Request &  req,
pses_ucbridge::GetSteeringLevel::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the current steering level.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested steering level info.
Returns
true is no errors occured, else false.

Definition at line 462 of file servicefunctions.h.

bool ServiceFunctions::getUSInfo ( pses_ucbridge::GetUSInfo::Request &  req,
pses_ucbridge::GetUSInfo::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to transmit the calibration of its ultra sonic range sensors.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call and the requested ultra sonic range sensor info.
Returns
true is no errors occured, else false.

Definition at line 495 of file servicefunctions.h.

bool ServiceFunctions::resetController ( pses_ucbridge::ResetController::Request &  req,
pses_ucbridge::ResetController::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to do perform a soft reset.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 526 of file servicefunctions.h.

bool ServiceFunctions::resetDMS ( pses_ucbridge::ResetDMS::Request &  req,
pses_ucbridge::ResetDMS::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to reset the counter on the dead man's switch.

Parameters
[in]reqRequest message is empty.
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 557 of file servicefunctions.h.

bool ServiceFunctions::setIMU ( pses_ucbridge::SetIMU::Request &  req,
pses_ucbridge::SetIMU::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to change the calibration of its IMU.

Parameters
[in]reqRequest message contains the new accel range, accel filter, gyro range and gyro filter values..
[out]resResponse message informs the calling process about the success of the service call and adds the new calibration from the imu.
Returns
true is no errors occured, else false.

Definition at line 585 of file servicefunctions.h.

bool ServiceFunctions::setMag ( pses_ucbridge::SetMag::Request &  req,
pses_ucbridge::SetMag::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device whether to use the magnetic field sensor calibration or not.

Parameters
[in]reqRequest message contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 624 of file servicefunctions.h.

bool ServiceFunctions::setMotorLevel ( pses_ucbridge::SetMotorLevel::Request &  req,
pses_ucbridge::SetMotorLevel::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to change the current motor level.

Parameters
[in]reqRequest contains the motor level
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 656 of file servicefunctions.h.

bool ServiceFunctions::setSessionID ( pses_ucbridge::SetSessionID::Request &  req,
pses_ucbridge::SetSessionID::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to set the current session id.

Parameters
[in]reqRequest contains the session id
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 694 of file servicefunctions.h.

bool ServiceFunctions::setSteeringLevel ( pses_ucbridge::SetSteering::Request &  req,
pses_ucbridge::SetSteering::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to change the current steering level.

Parameters
[in]reqRequest contains the steering level
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 725 of file servicefunctions.h.

bool ServiceFunctions::setUS ( pses_ucbridge::SetUS::Request &  req,
pses_ucbridge::SetUS::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to change the calibration of its ultra sonic range sensors.

Parameters
[in]reqRequest contains range and gain
[out]resResponse message informs the calling process about the success of the service call and adds the new calibration from the us.
Returns
true is no errors occured, else false.

Definition at line 756 of file servicefunctions.h.

bool ServiceFunctions::toggleBrakes ( pses_ucbridge::ToggleBrakes::Request &  req,
pses_ucbridge::ToggleBrakes::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate its motor brakes.

Parameters
[in]reqRequest contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 791 of file servicefunctions.h.

bool ServiceFunctions::toggleDAQ ( pses_ucbridge::ToggleDAQ::Request &  req,
pses_ucbridge::ToggleDAQ::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate the daq.

Parameters
[in]reqRequest contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 831 of file servicefunctions.h.

bool ServiceFunctions::toggleDMS ( pses_ucbridge::ToggleDMS::Request &  req,
pses_ucbridge::ToggleDMS::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate the dead man's switch.

Parameters
[in]reqRequest contains a bool (true=on, false=off) and the time interval in milliseconds.
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 867 of file servicefunctions.h.

bool ServiceFunctions::toggleGroup ( pses_ucbridge::ToggleGroup::Request &  req,
pses_ucbridge::ToggleGroup::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate a particular group.

Parameters
[in]reqRequest contains a bool (true=on, false=off) and the group number
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 904 of file servicefunctions.h.

bool ServiceFunctions::toggleKinect ( pses_ucbridge::ToggleKinect::Request &  req,
pses_ucbridge::ToggleKinect::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate the kinect power supply.

Parameters
[in]reqRequest contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 942 of file servicefunctions.h.

bool ServiceFunctions::toggleMotor ( pses_ucbridge::ToggleMotor::Request &  req,
pses_ucbridge::ToggleMotor::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate the motor controller.

Parameters
[in]reqRequest contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 981 of file servicefunctions.h.

bool ServiceFunctions::toggleUS ( pses_ucbridge::ToggleUS::Request &  req,
pses_ucbridge::ToggleUS::Response &  res,
Communication com 
)

A call to this Service will send a command to the serial device to activate/deactivate the ultra sonic range sensors.

Parameters
[in]reqRequest contains a bool (true=on, false=off)
[out]resResponse message informs the calling process about the success of the service call.
Returns
true is no errors occured, else false.

Definition at line 1020 of file servicefunctions.h.



pses_ucbridge
Author(s): Sebastian Ehmes
autogenerated on Sat Oct 28 2017 19:16:13