#include <algorithm>
#include <functional>
#include <sstream>
#include <XmlRpcValue.h>
#include <XmlRpcException.h>
#include <canopen_chain_node/GetObject.h>
#include <canopen_chain_node/SetObject.h>
#include <prbt_hardware_support/BrakeTest.h>
#include <prbt_hardware_support/BrakeTestErrorCodes.h>
#include <prbt_hardware_support/canopen_braketest_adapter.h>
#include <prbt_hardware_support/canopen_braketest_adapter_exception.h>
Go to the source code of this file.
Namespaces | |
prbt_hardware_support | |
Variables | |
static const std::string | prbt_hardware_support::CANOPEN_GETOBJECT_SERVICE_NAME { "/prbt/driver/get_object" } |
static const std::string | prbt_hardware_support::CANOPEN_NODES_PARAMETER_NAME { "/prbt/driver/nodes" } |
static const std::string | prbt_hardware_support::CANOPEN_SETOBJECT_SERVICE_NAME { "/prbt/driver/set_object" } |
static const std::string | prbt_hardware_support::GET_BRAKETEST_DURATION_OBJECT { "2060sub1" } |
static const std::string | prbt_hardware_support::GET_BRAKETEST_STATUS_OBJECT { "2060sub3" } |
static const std::string | prbt_hardware_support::NODE_BRAKETEST_ENABLED_PARAMETER { "braketest_required" } |
static const std::string | prbt_hardware_support::SET_START_BRAKETEST_OBJECT { "2060sub2" } |
static const std::string | prbt_hardware_support::TRIGGER_BRAKETEST_SERVICE_NAME { "/trigger_braketest" } |
static constexpr double | prbt_hardware_support::WAIT_FOR_SERVICE_TIMEOUT_S { 5.0 } |