Driver for the Mitsubishi RV2-AJ.
More...
#include <Driver.hpp>
|
| Driver (bool simulation, const std::optional< std::string > &serial_path) |
| Constructor. More...
|
|
virtual | ~Driver () |
| Destructor.
|
|
| Driver (const Driver &d)=delete |
| Copy constructor, deleted. More...
|
|
| Driver (Driver &&d)=delete |
| Move constructor, deleted. More...
|
|
Driver & | operator= (const Driver &d)=delete |
| Copy assignment operator, deleted. More...
|
|
Driver & | operator= (Driver &&d)=delete |
| Move assignment operator, deleted. More...
|
|
bool | cont (HLR::RV2AJDriverContinue::Request &req, HLR::RV2AJDriverContinue::Response &res) |
| Continue processing events in queue. More...
|
|
bool | pause (HLR::RV2AJDriverPause::Request &req, HLR::RV2AJDriverPause::Response &res) |
| Pause processing events in queue. More...
|
|
bool | clear (HLR::RV2AJDriverClear::Request &req, HLR::RV2AJDriverClear::Response &res) |
| Clears all to-be processed events in queue. More...
|
|
bool | queue_count (HLR::RV2AJDriverQueueCount::Request &req, HLR::RV2AJDriverQueueCount::Response &res) |
| Returns the number of elements currently inside the queue. More...
|
|
bool | queue_add (HLR::RV2AJDriverQueueAdd::Request &req, HLR::RV2AJDriverQueueAdd::Response &res) |
| Add requested command to the queue if compliant. More...
|
|
Driver for the Mitsubishi RV2-AJ.
HLR::Kinematics::RV2AJ::Driver::Driver |
( |
bool |
simulation, |
|
|
const std::optional< std::string > & |
serial_path |
|
) |
| |
Constructor.
- Parameters
-
simulation | enable simulation device |
serial_path | path to serial device, can be std::nullopt |
- Exceptions
-
std::invalid_argument | no enabled devices to drive |
HLR::Kinematics::RV2AJ::Driver::Driver |
( |
const Driver & |
d | ) |
|
|
delete |
Copy constructor, deleted.
- Parameters
-
HLR::Kinematics::RV2AJ::Driver::Driver |
( |
Driver && |
d | ) |
|
|
delete |
Move constructor, deleted.
- Parameters
-
bool HLR::Kinematics::RV2AJ::Driver::clear |
( |
HLR::RV2AJDriverClear::Request & |
req, |
|
|
HLR::RV2AJDriverClear::Response & |
res |
|
) |
| |
Clears all to-be processed events in queue.
- Parameters
-
req | Request details, empty |
res | Response details, empty |
- Returns
- true when queue is cleared, always
bool HLR::Kinematics::RV2AJ::Driver::cont |
( |
HLR::RV2AJDriverContinue::Request & |
req, |
|
|
HLR::RV2AJDriverContinue::Response & |
res |
|
) |
| |
Continue processing events in queue.
- Parameters
-
req | Request details, empty |
res | Response details, empty |
- Returns
- true if paused, false otherwise
Driver& HLR::Kinematics::RV2AJ::Driver::operator= |
( |
const Driver & |
d | ) |
|
|
delete |
Copy assignment operator, deleted.
- Parameters
-
- Returns
- Driver
Driver& HLR::Kinematics::RV2AJ::Driver::operator= |
( |
Driver && |
d | ) |
|
|
delete |
Move assignment operator, deleted.
- Parameters
-
- Returns
- Driver
bool HLR::Kinematics::RV2AJ::Driver::pause |
( |
HLR::RV2AJDriverPause::Request & |
req, |
|
|
HLR::RV2AJDriverPause::Response & |
res |
|
) |
| |
Pause processing events in queue.
- Parameters
-
req | Request details, empty |
res | Response details, empty |
- Returns
- true if not paused, false otherwise
bool HLR::Kinematics::RV2AJ::Driver::queue_add |
( |
HLR::RV2AJDriverQueueAdd::Request & |
req, |
|
|
HLR::RV2AJDriverQueueAdd::Response & |
res |
|
) |
| |
Add requested command to the queue if compliant.
- Parameters
-
req | Request details, containing angles and speed |
res | Response details, empty |
- Returns
- true when queued, false if invalid input or robot arm failing
bool HLR::Kinematics::RV2AJ::Driver::queue_count |
( |
HLR::RV2AJDriverQueueCount::Request & |
req, |
|
|
HLR::RV2AJDriverQueueCount::Response & |
res |
|
) |
| |
Returns the number of elements currently inside the queue.
- Parameters
-
req | Request details, empty |
res | Response details, containing count |
- Returns
- true when queue count is set in response, always
The documentation for this class was generated from the following file: