Namespaces | Classes | Typedefs | Functions | Variables
prbt_hardware_support Namespace Reference

Namespaces

 modbus_api
 
 modbus_api_spec
 

Classes

class  AdapterOperationMode
 Publishes information on the active operation mode. Also offers a service for querying the operation mode. More...
 
class  AsyncRunPermittedTask
 An AsyncRunPermittedTask is represented by a task execution and a completion signalling. More...
 
class  BrakeTestExecutor
 Triggers execution of brake tests only if the controller is not executing a trajectory. More...
 
class  BrakeTestExecutorException
 
class  BrakeTestRequiredIntegrationTest
 BrakeTestRequiredIntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> ModbusAdapterBrakeTest functions properly. More...
 
class  BrakeTestUtils
 
class  BrakeTestUtilsException
 Exception thrown by a BrakeTestUtils function. More...
 
class  CANOpenBrakeTestAdapter
 Executes the brake test for all joints. A brake test is triggered via service call. More...
 
class  CANOpenBrakeTestAdapterException
 Exception thrown by the CANOpenBrakeTestAdapter. More...
 
class  CANOpenChainNodeMock
 
class  FakeSpeedOverrideTest
 
class  FilterPipeline
 An abstraction of a series of filters which ensures that only Modbus messages with different timestamps pass the pipeline. More...
 
class  GetCurrentJointStatesException
 Expection thrown by BrakeTestUtils::getCurrentJointStates(). More...
 
class  JointStatesPublisherMock
 Asynchronously publishes predefined messages on the /joint_states topic with rate ~100Hz. More...
 
class  LibModbusClient
 Wrapper around libmodbus, see https://libmodbus.org/. More...
 
class  ModbusAdapterBrakeTest
 Listens to the modbus_read topic and publishes a message informing about a required brake test. More...
 
class  ModbusAdapterBrakeTestException
 Exception thrown by the ModbusAdapterBrakeTest class. More...
 
class  ModbusAdapterOperationMode
 Listens to the modbus_read topic and offers a service informing about the active operation mode. More...
 
class  ModbusAdapterOperationModeTest
 Test fixture for unit-tests of the ModbusAdapterOperationMode. More...
 
class  ModbusAdapterRunPermitted
 Listens to the modbus_read topic and reacts to updated RUN_PERMITTED states. More...
 
class  ModbusAdapterRunPermittedTest
 
class  ModbusApiSpecException
 Expection thrown by prbt_hardware_support::ModbusApiSpec. More...
 
class  ModbusApiSpecTemplated
 Specifies the meaning of the holding registers. More...
 
class  ModbusClient
 
class  ModbusMock
 
class  ModbusMsgBrakeTestWrapper
 Wrapper class to add semantic to a raw ModbusMsgInStamped. More...
 
class  ModbusMsgBrakeTestWrapperException
 Expection thrown upon construction of ModbusMsgBrakeTestWrapper of the message does not contain the required information. More...
 
class  ModbusMsgInBuilder
 Help on construction for ModbusMsgIn Messages. More...
 
class  ModbusMsgOperationModeWrapper
 Wrapper class to add semantic to a raw ModbusMsgInStamped. More...
 
class  ModbusMsgOperationModeWrapperException
 Expection thrown upon construction of ModbusMsgOperationModeWrapper of the message does not contain the required information. More...
 
class  ModbusMsgRunPermittedStatusMissing
 Expection thrown upon construction of ModbusMsgRunPermittedWrapper if the message does not contain the required information. More...
 
class  ModbusMsgRunPermittedWrapper
 Wrapper class to add semantic to a raw ModbusMsgInStamped. More...
 
class  ModbusMsgWrapper
 Wrapper class to add semantic to a raw ModbusMsgInStamped. More...
 
class  ModbusMsgWrapperException
 Expection thrown upon construction of ModbusMsgWrapperBase of the message does not contain the required information. More...
 
class  OperationModeIntegrationTest
 OperationModeIntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> ModbusAdapterOperationMode functions properly. More...
 
class  OperationModeSetupExecutor
 Sets the allowed speed limit for each frame based on the current operation mode. More...
 
class  OperationModeSubscriberMock
 Redirects callbacks of a ros::Subscriber to a mock method. More...
 
class  PilzModbusClient
 Connects to a modbus server and publishes the received data into ROS. More...
 
class  PilzModbusClientException
 Expection thrown by prbt_hardware_support::PilzModbusClient. More...
 
class  PilzModbusServerMock
 Offers a modbus server and read/write functionality via subscription/publication. More...
 
class  RunPermittedStateMachine_
 Front-end state machine. More...
 
class  ServiceMock
 
class  SpeedObserver
 
class  Stop1Executor
 Performs service calls for Stop1 and the respective reversal, that is enabling the manipulator. Incoming updates of the RUN_PERMITTED state are handled asynchronously. More...
 
class  Stop1IntegrationTest
 Stop1IntegrationTest checks if the chain ModbusServerMock -> ModbusReadClient -> RunPermittedModbusAdapter -> ManipulatorMock functions properly. More...
 
class  Stop1ServiceMissingIntegrationTest
 Test the stop1 startup with a missing service. More...
 
class  SystemInfo
 Provides easy access to system information which are of importance when analyzing bugs. More...
 
class  SystemInfoException
 Exception thrown by the SystemInfo class in case of an error. More...
 

Typedefs

using BrakeTestResultFunc = std::function< bool(const bool)>
 
using ControllerHoldFunc = std::function< void()>
 
using ControllerUnholdFunc = std::function< void()>
 
using DetectRobotMotionFunc = std::function< bool()>
 
using FirmwareCont = std::map< std::string, std::string >
 
using GetOpModeFunc = std::function< OperationModes()>
 
typedef ModbusApiSpecTemplated ModbusApiSpec
 Simple typedef for class like usage. More...
 
using RegCont = std::vector< uint16_t >
 Convenience data type defining the data type for a collection of registers. More...
 
typedef msm::back::state_machine< RunPermittedStateMachine_RunPermittedStateMachine
 The top-level (back-end) state machine. More...
 
using RunPermittedTaskQueue = std::queue< AsyncRunPermittedTask >
 Define the task queue type. More...
 
using SetSpeedLimitFunc = std::function< bool(const double &)>
 
using TriggerBrakeTestFunc = std::function< BrakeTest::Response()>
 
using TServiceCallFunc = std::function< bool()>
 
using TWriteModbusRegister = std::function< bool(const uint16_t &, const RegCont &)>
 
using UpdateRunPermittedFunc = std::function< void(const bool)>
 

Functions

bool brakeTestRegisterSetOnServer (PilzModbusServerMock &server, unsigned short register_perf, unsigned short register_res, uint16_t expectation, float sleep_per_try_s, unsigned short retries)
 
bool callService (ros::ServiceClient &srv_client)
 
bool checkForNode (std::string node_name)
 Checks if a node is up and running. More...
 
std::string className (std::string full_name)
 
static ModbusMsgInStampedPtr createDefaultBrakeTestModbusMsg (const uint16_t brake_test_required_value, const unsigned int modbus_api_version=MODBUS_API_VERSION_REQUIRED, const uint32_t brake_test_required_index=TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::BRAKETEST_REQUEST))
 
template<class T >
static BrakeTest::Response executeBrakeTestCall (T &client)
 
::testing::AssertionResult expectBrakeTestRequiredServiceCallResult (ros::ServiceClient &brake_test_required_client, IsBrakeTestRequiredResponse::_result_type expectation, uint16_t retries=DEFAULT_RETRIES)
 
template<class T >
static void initalizeAndRun (T &obj, const char *ip, unsigned int port)
 
 MATCHER_P (IsExpectedOperationMode, exp_mode,"unexpected operation mode")
 
template<class T >
static bool sendBrakeTestResultCall (T &client, const bool brake_test_result)
 
template<class T >
static bool setSpeedLimitSrv (T &srv_client, const double &speed_limit)
 
 TEST (FilterPipelineTest, testEmptyCallbackFunction)
 Tests that exception is thrown if empty callback function is specified. More...
 
 TEST (ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperExceptionDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST (IntegrationtestExecuteBrakeTest, testBrakeTestService)
 
 TEST (ModbusAdapterBrakeTestTest, testModbusMsgBrakeTestWrapperDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST (ModbusAdapterBrakeTestTest, testNoMessageReceived)
 
 TEST (ModbusAdapterBrakeTestTest, testBrakeTestRequired)
 
 TEST (ModbusAdapterBrakeTestTest, testBrakeTestNotRequired)
 
 TEST (ModbusAdapterBrakeTestTest, testDisconnect)
 
 TEST (ModbusAdapterBrakeTestTest, testModbusIncorrectApiVersion)
 
 TEST (ModbusAdapterBrakeTestTest, testModbusWithoutApiVersion)
 
 TEST (ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterMissing)
 
 TEST (ModbusAdapterBrakeTestTest, testBrakeTestRequiredRegisterUndefinedValue)
 
 TEST (ModbusAdapterBrakeTestTest, testModbusApiSpecExceptionDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST (ModbusAdapterBrakeTestTest, testBrakeTestTriggeringWrongApiDef)
 Test execution of brake tests when there is a problem in the api definition. More...
 
 TEST (ModbusAdapterBrakeTestTest, testMissingModbusWriteFunc)
 Tests that missing modbus register write functions leads to response.success==false. More...
 
 TEST (ModbusAdapterBrakeTestTest, testFailingModbusWriteFunc)
 Tests that failing modbus register write functions leads to response.success==false. More...
 
 TEST (ModbusAdapterBrakeTestTest, testSecondTimeFailingModbusWriteFunc)
 Tests that failing modbus register write functions leads to response.success==false. More...
 
 TEST (ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallResponseFalse)
 Tests that a service.response=false leads to return value false. More...
 
 TEST (ModbusAdapterBrakeTestTest, testWriteModbusRegisterCallFailure)
 Tests that a service call failure leads to return value false. More...
 
 TEST_F (FakeSpeedOverrideTest, defaultSpeedOverride)
 
 TEST_F (ModbusAdapterRunPermittedTest, testModbusMsgWrapperExceptionDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST_F (FakeSpeedOverrideTest, testSettingSpeedOverride)
 
 TEST_F (ModbusAdapterRunPermittedTest, testModbusMsgRunPermittedWrapperDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST_F (FakeSpeedOverrideTest, testSettingSpeedOverrideToLow)
 
 TEST_F (ModbusAdapterRunPermittedTest, testRunPermittedClearMsg)
 Tests that a modbus message giving run_permitted clearance leads to RUN_PERMITTED clear message. More...
 
 TEST_F (FakeSpeedOverrideTest, testSettingSpeedOverrideToHigh)
 
 TEST_F (ModbusAdapterRunPermittedTest, testRunPermittedActiveMsg)
 Tests that a modbus message giving RUN_PERMITTED leads to RUN_PERMITTED active message. More...
 
 TEST_F (Stop1ServiceMissingIntegrationTest, testMissingService)
 Test that the startup of the stop1_executor is not complete if a service is missing. More...
 
 TEST_F (OperationModeIntegrationTest, testOperationModeRequestAnnouncement)
 
 TEST_F (ModbusAdapterRunPermittedTest, testDisconnectNoRunPermittedMsg)
 
 TEST_F (ModbusAdapterOperationModeTest, testAdapterOperationModeDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST_F (BrakeTestRequiredIntegrationTest, testBrakeTestAnnouncement)
 
 TEST_F (ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperExceptionDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST_F (ModbusAdapterRunPermittedTest, testDisconnectWithRunPermittedMsg)
 
 TEST_F (ModbusAdapterOperationModeTest, testModbusMsgOperationModeWrapperDtor)
 Test increases function coverage by ensuring that all Dtor variants are called. More...
 
 TEST_F (Stop1IntegrationTest, testServiceCallbacks)
 Test that correct service calls occurs based on RUN_PERMITTED state. More...
 
 TEST_F (ModbusAdapterOperationModeTest, testInitialOperationMode)
 Tests that initial operation mode is UNKNOWN. More...
 
 TEST_F (ModbusAdapterRunPermittedTest, testDisconnectPure)
 
 TEST_F (ModbusAdapterRunPermittedTest, testNoVersion)
 
 TEST_F (ModbusAdapterOperationModeTest, testMissingOperationModeRegister)
 
 TEST_F (ModbusAdapterRunPermittedTest, testWrongVersion)
 
 TEST_F (ModbusAdapterRunPermittedTest, testVersion1)
 
 TEST_F (ModbusAdapterRunPermittedTest, testNoRunPermitted)
 
 TEST_F (ModbusAdapterRunPermittedTest, ModbusMsgExceptionCTOR)
 Check construction of the exception (essentially for full function coverage) More...
 
 TEST_F (ModbusAdapterOperationModeTest, testOperationModeChange)
 
 TEST_F (ModbusAdapterOperationModeTest, testDisconnect)
 
 TEST_F (ModbusAdapterOperationModeTest, testModbusUnexpectedOperationMode)
 
 TEST_F (ModbusAdapterOperationModeTest, testModbusIncorrectApiVersion)
 
bool triggerCallbackDummy (std_srvs::TriggerRequest &req, std_srvs::TriggerResponse &resp)
 
template<class T >
static void triggerServiceCall (T &client)
 
void waitForNode (std::string node_name, double loop_frequency=10.0)
 Blocks until a node defined by node_name comes up. More...
 
inline::testing::AssertionResult waitForNodeShutdown (std::string node_name, double timeout=1.0, double loop_frequency=10.0)
 Blocks until a node defined by node_name can no longer be found. More...
 
template<class T >
static bool writeModbusRegisterCall (T &modbus_service, const uint16_t &start_idx, const RegCont &values)
 

Variables

static const std::string BRAKE_TEST_DURATION_OBJECT_INDEX {"2060sub1"}
 
static constexpr unsigned int BRAKE_TEST_PERFORMED {1}
 
static const std::string BRAKE_TEST_STATUS_OBJECT_INDEX {"2060sub3"}
 
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
 
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
 
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
 
static const std::string CANOPEN_NODES_PARAMETER_NAME {"/prbt/driver/nodes"}
 
static const std::string CANOPEN_NODES_PARAMETER_NAME {"/prbt/driver/nodes"}
 
static const std::string CANOPEN_SETOBJECT_SERVICE_NAME {"/prbt/driver/set_object"}
 
static const std::string CANOPEN_SETOBJECT_SERVICE_NAME {"/prbt/driver/set_object"}
 
static constexpr unsigned int DEFAULT_ALLOWED_MISSED_CALCULATIONS {3}
 Allowed number of missed calculations. If it is exceeded a Stop1 is triggered. More...
 
static constexpr int DEFAULT_QUEUE_SIZE {10}
 
static constexpr int DEFAULT_QUEUE_SIZE_MODBUS {1}
 
static constexpr unsigned int DEFAULT_RETRIES {10}
 
static constexpr double EXPECTED_DEFAULT_SPEED_OVERRIDE {1.0}
 
static constexpr std::size_t FIRMWARE_STRING_LENGTH {40}
 
static const std::string FRAME_SPEEDS_TOPIC_NAME { "frame_speeds" }
 
static const std::string GET_BRAKETEST_DURATION_OBJECT {"2060sub1"}
 
static const std::string GET_BRAKETEST_STATUS_OBJECT {"2060sub3"}
 
static const std::string GET_FIRMWARE_VERION_OBJECT {"100A"}
 
static const std::string HALT_SERVICE_NAME {"halt"}
 
static const std::string HALT_SERVICE_NAME {"halt"}
 
static const std::string HOLD_SERVICE_NAME {"hold"}
 
static const std::string HOLD_SERVICE_NAME {"hold"}
 
static const std::string JOINT_STATE_TOPIC {"/joint_states"}
 
static const std::string JOINT_STATES_TOPIC_NAME {"/prbt/joint_states"}
 
static constexpr unsigned int JOINT_STATES_TOPIC_QUEUE_SIZE {1}
 
constexpr const char *const LOCALHOST = "127.0.0.1"
 
static constexpr int MODBUS_API_VERSION_FOR_TESTING {2}
 
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED {2}
 
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED {2}
 
static constexpr unsigned int MODBUS_API_VERSION_REQUIRED {2}
 
static constexpr uint16_t MODBUS_API_VERSION_VALUE {2}
 
static constexpr uint16_t MODBUS_API_VERSION_VALUE {2}
 
static constexpr uint16_t MODBUS_API_VERSION_VALUE {2}
 
static const std::string MODBUS_SERVICE_NAME {"/pilz_modbus_client_node/modbus_write"}
 
static const std::string NODE_BRAKETEST_ENABLED_PARAMETER {"braketest_required"}
 
static const std::string OMIT_SERVICE_PARAM_NAME {"omit_service"}
 
static const std::string OPERATION_MODE_CALLBACK_EVENT {"operation_mode_callback_event"}
 
static const std::string OPERATION_MODE_CALLBACK_EVENT {"operation_mode_callback_event"}
 
static constexpr int OPERATION_MODE_QUEUE_SIZE {1}
 
static constexpr int OPERATION_MODE_QUEUE_SIZE {1}
 
static const std::vector< uint16_t > OPERATION_MODES {1, 2, 3}
 
static const std::string PARAM_INDEX_OF_FIRST_REGISTER_TO_READ_STR {"index_of_first_register_to_read"}
 
static const std::string PARAM_MODBUS_CONNECTION_RETRIES {"modbus_connection_retries"}
 
static const std::string PARAM_MODBUS_CONNECTION_RETRY_TIMEOUT {"modbus_connection_retry_timeout"}
 
static const std::string PARAM_MODBUS_READ_TOPIC_NAME_STR {"modbus_read_topic_name"}
 
static const std::string PARAM_MODBUS_RESPONSE_TIMEOUT_STR {"modbus_response_timeout"}
 
static const std::string PARAM_MODBUS_SERVER_IP_STR {"modbus_server_ip"}
 
static const std::string PARAM_MODBUS_SERVER_PORT_STR {"modbus_server_port"}
 
static const std::string PARAM_MODBUS_WRITE_SERVICE_NAME_STR {"modbus_write_service_name"}
 
static const std::string PARAM_NUM_REGISTERS_TO_READ_STR {"num_registers_to_read"}
 
static const std::string READ_API_SPEC_PARAM_NAME {"read_api_spec/"}
 
static const std::string RECOVER_SERVICE_NAME {"recover"}
 
static const std::string RECOVER_SERVICE_NAME {"recover"}
 
static constexpr uint16_t REGISTER_VALUE_BRAKETEST_NOT_REQUIRED {0}
 
static constexpr uint16_t REGISTER_VALUE_BRAKETEST_REQUIRED {1}
 
static constexpr bool RUN_PERMITTED_ACTIVE {false}
 
static constexpr bool RUN_PERMITTED_CLEAR {true}
 
static const std::string RUN_PERMITTED_SERVICE { "run_permitted" }
 
static const std::string SERVICE_BRAKETEST_REQUIRED = "/prbt/brake_test_required"
 
static const std::string SERVICE_MODBUS_WRITE = "/pilz_modbus_client_node/modbus_write"
 
static const std::string SERVICE_NAME_GET_OPERATION_MODE = "/prbt/get_operation_mode"
 
static const std::string SERVICE_NAME_OPERATION_MODE = "/prbt/get_operation_mode"
 
static const std::string SET_START_BRAKETEST_OBJECT {"2060sub2"}
 
static const std::string START_BRAKE_TEST_OBJECT_INDEX {"2060sub2"}
 
static const std::string STOP1_EXECUTOR_NODE_NAME {"/stop1_executor_node"}
 
static const ModbusApiSpec TEST_API_SPEC
 
static const ModbusApiSpec TEST_API_SPEC
 
static const ModbusApiSpec test_api_spec
 
static const ModbusApiSpec TEST_API_WRITE_SPEC
 
static const std::string TOPIC_MODBUS_READ = "/pilz_modbus_client_node/modbus_read"
 
static const std::string TOPIC_OPERATION_MODE = "/prbt/operation_mode"
 
static const std::string TOPIC_OPERATION_MODE {"/prbt/operation_mode"}
 
static const std::string TOPIC_OPERATION_MODE {"/prbt/operation_mode"}
 
static const std::string TRIGGER_BRAKETEST_SERVICE_NAME {"/trigger_braketest"}
 
static const std::string UNHOLD_SERVICE_NAME {"unhold"}
 
static const std::string UNHOLD_SERVICE_NAME {"unhold"}
 
static constexpr double WAIT_FOR_NODE_SLEEPTIME_S {5.0}
 
static constexpr double WAIT_FOR_SERVICE_TIMEOUT_S {5.0}
 

Typedef Documentation

using prbt_hardware_support::BrakeTestResultFunc = typedef std::function<bool(const bool)>

Definition at line 36 of file brake_test_executor.h.

using prbt_hardware_support::ControllerHoldFunc = typedef std::function<void()>

Definition at line 33 of file brake_test_executor.h.

using prbt_hardware_support::ControllerUnholdFunc = typedef std::function<void()>

Definition at line 35 of file brake_test_executor.h.

using prbt_hardware_support::DetectRobotMotionFunc = typedef std::function<bool()>

Definition at line 32 of file brake_test_executor.h.

using prbt_hardware_support::FirmwareCont = typedef std::map<std::string, std::string>

key = joint_name value = firmware version of joint

Definition at line 34 of file system_info.h.

using prbt_hardware_support::GetOpModeFunc = typedef std::function<OperationModes()>

Definition at line 27 of file get_operation_mode_func_decl.h.

Simple typedef for class like usage.

Definition at line 193 of file modbus_api_spec.h.

using prbt_hardware_support::RegCont = typedef std::vector<uint16_t>

Convenience data type defining the data type for a collection of registers.

Definition at line 27 of file register_container.h.

The top-level (back-end) state machine.

Definition at line 375 of file run_permitted_state_machine.h.

Define the task queue type.

Definition at line 87 of file run_permitted_state_machine.h.

using prbt_hardware_support::SetSpeedLimitFunc = typedef std::function<bool(const double&)>

Definition at line 25 of file set_speed_limit_func_decl.h.

using prbt_hardware_support::TriggerBrakeTestFunc = typedef std::function<BrakeTest::Response()>

Definition at line 34 of file brake_test_executor.h.

using prbt_hardware_support::TServiceCallFunc = typedef std::function<bool()>

Definition at line 26 of file service_function_decl.h.

using prbt_hardware_support::TWriteModbusRegister = typedef std::function<bool(const uint16_t&, const RegCont&)>

Definition at line 37 of file modbus_adapter_brake_test.h.

using prbt_hardware_support::UpdateRunPermittedFunc = typedef std::function<void(const bool)>

Definition at line 32 of file modbus_adapter_run_permitted.h.

Function Documentation

bool prbt_hardware_support::brakeTestRegisterSetOnServer ( PilzModbusServerMock server,
unsigned short  register_perf,
unsigned short  register_res,
uint16_t  expectation,
float  sleep_per_try_s,
unsigned short  retries 
)

Definition at line 42 of file integrationtest_execute_brake_test.cpp.

bool prbt_hardware_support::callService ( ros::ServiceClient srv_client)

Definition at line 34 of file stop1_executor_node.cpp.

bool prbt_hardware_support::checkForNode ( std::string  node_name)
inline

Checks if a node is up and running.

Parameters
node_name
Returns
True if the node was found, false otherwise.

Definition at line 35 of file ros_test_helper.h.

std::string prbt_hardware_support::className ( std::string  full_name)
inline

Definition at line 26 of file utils.h.

static ModbusMsgInStampedPtr prbt_hardware_support::createDefaultBrakeTestModbusMsg ( const uint16_t  brake_test_required_value,
const unsigned int  modbus_api_version = MODBUS_API_VERSION_REQUIRED,
const uint32_t  brake_test_required_index = TEST_API_SPEC.getRegisterDefinition(modbus_api_spec::BRAKETEST_REQUEST) 
)
static

Definition at line 58 of file unittest_modbus_adapter_brake_test.cpp.

template<class T >
static BrakeTest::Response prbt_hardware_support::executeBrakeTestCall ( T &  client)
static

Definition at line 51 of file brake_test_executor_node_service_calls.h.

::testing::AssertionResult prbt_hardware_support::expectBrakeTestRequiredServiceCallResult ( ros::ServiceClient brake_test_required_client,
IsBrakeTestRequiredResponse::_result_type  expectation,
uint16_t  retries = DEFAULT_RETRIES 
)

Definition at line 88 of file integrationtest_brake_test_required.cpp.

template<class T >
static void prbt_hardware_support::initalizeAndRun ( T &  obj,
const char *  ip,
unsigned int  port 
)
static

Definition at line 83 of file ros_test_helper.h.

prbt_hardware_support::MATCHER_P ( IsExpectedOperationMode  ,
exp_mode  ,
"unexpected operation mode"   
)

Definition at line 81 of file integrationtest_operation_mode.cpp.

template<class T >
static bool prbt_hardware_support::sendBrakeTestResultCall ( T &  client,
const bool  brake_test_result 
)
static

Definition at line 68 of file brake_test_executor_node_service_calls.h.

template<class T >
static bool prbt_hardware_support::setSpeedLimitSrv ( T &  srv_client,
const double &  speed_limit 
)
static
prbt_hardware_support::TEST ( FilterPipelineTest  ,
testEmptyCallbackFunction   
)

Tests that exception is thrown if empty callback function is specified.

Definition at line 31 of file unittest_filter_pipeline.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testModbusMsgBrakeTestWrapperExceptionDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 79 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( IntegrationtestExecuteBrakeTest  ,
testBrakeTestService   
)
  • Test the BrakeTest service node. (Spec)

Test Sequence:

  1. Preparing modbus mock
  2. Initialize CANOpen mock, JointStatesPublisher mock and manipulator mock
  3. Wait for BrakeTest service
  4. Make the service call
  5. Check contents of relevant modbus registers
  6. Shutdown of modbus mock

Expected Results:

  1. -
  2. -
  3. Service is available
  4. Service call is successful
  5. Brake test success was set in modbus
  6. -

Definition at line 85 of file integrationtest_execute_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testModbusMsgBrakeTestWrapperDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 88 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testNoMessageReceived   
)
  • Tests the value returned if no modbus messages are (Spec)

Test Sequence:

  1. Call service without sending a message via modbus before

Expected Results:

  1. The service returns true, and the it is unknown if a braketest has to be performed

Definition at line 107 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testBrakeTestRequired   
)
  • Tests the handling of an incoming modbus message informing about a required brake test. (Spec)

Test Sequence:

  1. Publish modbus message informing about a required brake test.

Expected Results:

  1. The service returns true

Definition at line 131 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testBrakeTestNotRequired   
)
  • Tests the handling of an incoming modbus message informing about a brake test not being required. (Spec)

Test Sequence:

  1. Publish modbus message informing about a brake test not being required.

Expected Results:

  1. The service returns false

Definition at line 156 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testDisconnect   
)
  • Tests the handling of an incoming modbus message informing about a disconnect. (Spec)

Test Sequence:

  1. Publish modbus message informing about a disconnect.

Expected Results:

  1. The state is unknown

Definition at line 181 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testModbusIncorrectApiVersion   
)
  • Tests the handling of an incoming modbus message with incorrect api version. (Spec)

Test Sequence:

  1. Publish modbus message with incorrect api version.

Expected Results:

  1. The state is unknown

Definition at line 211 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testModbusWithoutApiVersion   
)
  • Tests the handling of an incoming modbus message without api version. (Spec)

Test Sequence:

  1. Publish modbus message without api version.

Expected Results:

  1. The state is unknown

Definition at line 235 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testBrakeTestRequiredRegisterMissing   
)
  • Tests the handling of an incoming modbus message without a brake test status. (Spec)

Test Sequence:

  1. Publish modbus message without a brake test status.

Expected Results:

  1. The state is unknown

Definition at line 265 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testBrakeTestRequiredRegisterUndefinedValue   
)
  • Tests the handling of an incoming modbus message with a undefined brake test status register value. (Spec)

Test Sequence:

  1. Publish modbus message with a undefine brake test status register value.

Expected Results:

  1. The state is unknown

Definition at line 291 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testModbusApiSpecExceptionDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 308 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testBrakeTestTriggeringWrongApiDef   
)

Test execution of brake tests when there is a problem in the api definition.

Test Sequence:

  1. Execute a brake test with missing definition for BRAKETEST_PERFORMED
  2. Execute a brake test with missing definition for BRAKETEST_RESULT
  3. Execute a brake test with both values defined 1 apart
  4. Execute a brake test with both values defined 2 apart

Expected Results:

  1. A BrakeTestExecutorException is thown
  2. A BrakeTestExecutorException is thown
  3. No Exception is thrown
  4. A BrakeTestExecutorException is thown

Definition at line 329 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testMissingModbusWriteFunc   
)

Tests that missing modbus register write functions leads to response.success==false.

Definition at line 383 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testFailingModbusWriteFunc   
)

Tests that failing modbus register write functions leads to response.success==false.

Definition at line 398 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testSecondTimeFailingModbusWriteFunc   
)

Tests that failing modbus register write functions leads to response.success==false.

Definition at line 414 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testWriteModbusRegisterCallResponseFalse   
)

Tests that a service.response=false leads to return value false.

Definition at line 436 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST ( ModbusAdapterBrakeTestTest  ,
testWriteModbusRegisterCallFailure   
)

Tests that a service call failure leads to return value false.

Definition at line 451 of file unittest_modbus_adapter_brake_test.cpp.

prbt_hardware_support::TEST_F ( FakeSpeedOverrideTest  ,
defaultSpeedOverride   
)
  • Tests the default value of the fake speed override. (Spec)
  • Tests the default value of the fake speed override. (Spec)

Definition at line 72 of file unittest_fake_speed_override.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testModbusMsgWrapperExceptionDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 76 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( FakeSpeedOverrideTest  ,
testSettingSpeedOverride   
)

Definition at line 78 of file unittest_fake_speed_override.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testModbusMsgRunPermittedWrapperDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 85 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( FakeSpeedOverrideTest  ,
testSettingSpeedOverrideToLow   
)

Definition at line 89 of file unittest_fake_speed_override.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testRunPermittedClearMsg   
)

Tests that a modbus message giving run_permitted clearance leads to RUN_PERMITTED clear message.

Definition at line 96 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( FakeSpeedOverrideTest  ,
testSettingSpeedOverrideToHigh   
)

Definition at line 97 of file unittest_fake_speed_override.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testRunPermittedActiveMsg   
)

Tests that a modbus message giving RUN_PERMITTED leads to RUN_PERMITTED active message.

Definition at line 108 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( Stop1ServiceMissingIntegrationTest  ,
testMissingService   
)

Test that the startup of the stop1_executor is not complete if a service is missing.

  • Test that the startup of the stop1_executor is not complete if a service is missing. (Spec)

Test Sequence:

  1. Advertise all but one manipulator services
  2. Advertise missing service from step 1

Expected Results:

  1. Stop1 executor node does not come up
  2. Stop1 executor node does complete startup

Definition at line 111 of file integrationtest_stop1_service_missing.cpp.

prbt_hardware_support::TEST_F ( OperationModeIntegrationTest  ,
testOperationModeRequestAnnouncement   
)
  • Test that the expected result is obtained on the operation mode topic. (Spec)
Note
Due to the asynchronicity of the test each step of the sequence passed successful allows the next step to be taken. See testing::AsyncTest for details.

Data send via: ModbusServerMock -> ModbusReadClient -> ModbusAdapterOperationMode

Test Sequence:

  1. Start Modbus-server in separate thread. Make sure that the nodes are up and subscribe to operation mode topic.
  2. Send message with T1 in operation mode register and with the correct API version.
  3. Send message with 0 (unknown) in operation mode register and with the correct API version.
  4. Send message with T2 in operation mode register and with the correct API version.
  5. Send message with AUTO in operation mode register and with the correct API version.
  6. Send message with 99 (unknown) in operation mode register and with the correct API version.
  7. Terminate ModbusServerMock.

Expected Results:

  1. A message with unknown operation mode is obtained
  2. A message with T1 operation mode is obtained
  3. A message with unknown operation mode is obtained
  4. A message with T2 operation mode is obtained
  5. A message with AUTO operation mode is obtained
  6. A message with unknown operation mode is obtained
  7. -

Definition at line 112 of file integrationtest_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testDisconnectNoRunPermittedMsg   
)
  • Tests that a modbus message indicating a disconnect from modbus leads to RUN_PERMITTED active message even if the recieved modbus message content would give run_permitted clearance. (Spec)

Definition at line 123 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testAdapterOperationModeDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 125 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( BrakeTestRequiredIntegrationTest  ,
testBrakeTestAnnouncement   
)
  • Test that brake test required service returns correct value. (Spec)
Note
Due to the asynchronicity of the test each step of the sequence passed successful allows the next step to be taken. See testing::AsyncTest for details.

Data are send via: ModbusServerMock -> ModbusReadClient -> ModbusAdapterBrakeTest connection

Test Sequence:

  1. Start Modbus-server in separate thread. Make sure that the nodes are up.
  2. Send a brake test required message with the correct API version.
  3. Send a brake test required message with the correct API version (change another but irrelevant register entry).
  4. Send a brake test not-required message with the correct API version.
  5. Terminate ModbusServerMock.

Expected Results:

  1. -
  2. A service call is successfull and returns a positive result.
  3. A service call is successfull and returns a positive result.
  4. A service call is successfull and returns a negative result.
  5. -

Definition at line 132 of file integrationtest_brake_test_required.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testModbusMsgOperationModeWrapperExceptionDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 134 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testDisconnectWithRunPermittedMsg   
)
  • Tests that a modbus message indicating a disconnect from modbus leads to RUN_PERMITTED active message if the received the modbus message itself would also require run_permitted to go active. (Spec)

Definition at line 142 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testModbusMsgOperationModeWrapperDtor   
)

Test increases function coverage by ensuring that all Dtor variants are called.

Definition at line 143 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( Stop1IntegrationTest  ,
testServiceCallbacks   
)

Test that correct service calls occurs based on RUN_PERMITTED state.

  • Test that drives are recovered and controller is unhold after RUN_PERMITTED switch: false->true. (Spec)
  • Test that Stop 1 is triggered if RUN_PERMITTED value changes to false. (Spec)
Note
Due to the asynchronicity of the test each step of the sequence passed successful allows the next step to be taken. See testing::AsyncTest for details.

Data send via: ModbusServerMock -> ModbusReadClient -> RunPermittedModbusAdapter -> ManipulatorMock connection

Test Sequence:

  1. Start Modbus-server in seperate thread. Make sure that the nodes are up. Send a RUN_PERMITTED clear message with the correct API version.
  2. Send a RUN_PERMITTED active message with the correct API version.
  3. Send a RUN_PERMITTED clear message with the correct API version.
  4. Terminate Modbus-server to cause a disconnect.

Expected Results:

  1. The manipulator mock should receive a call to /recover after that a call to /unhold. No other calls should happen.
  2. The manipulator mock should receive a call to /hold after that a call to /halt. No other calls should happen.
  3. The manipulator mock should receive a call to /recover after that a call to /unhold. No other calls should happen.
  4. The manipulator mock should receive a call to /hold after that a call to /halt. No other calls should happen.

Definition at line 149 of file integrationtest_stop1.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testInitialOperationMode   
)

Tests that initial operation mode is UNKNOWN.

Waits for callback and calls service.

Definition at line 157 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testDisconnectPure   
)
  • Tests that a modbus message indicating a disconnect from modbus with no other data defined in the modbus message leads to RUN_PERMITTED active message (Spec)

Definition at line 159 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testNoVersion   
)
  • Tests that RUN_PERMITTED active message is send if no version is defined in modbus message. (Spec)

Definition at line 178 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testMissingOperationModeRegister   
)
  • Tests that operation mode UNKNOWN is returned if the operation mode register is missing in the modbus message. (Spec)

Test Sequence:

  1. Subscribe to operation modes topic.
  2. Send modbus message containing operation mode T1.
  3. Send modbus message which does not contain an operation mode.

Expected Results:

  1. Operation mode UNKNOWN is published.
  2. Operation mode T1 is published.
  3. Operation mode UNKNOWN is published.

Definition at line 187 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testWrongVersion   
)
  • Tests that RUN_PERMITTED active message is send if the modbus message contains a incorrect version number. (Spec)

Definition at line 195 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testVersion1   
)
  • Tests that RUN_PERMITTED active message is send if the modbus message contains version 1. (Spec)
Note
Version 1 had mistake in specification on the hardware therefore not supported at all.

Definition at line 216 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
testNoRunPermitted   
)
  • Test that RUN_PERMITTED active message is send if the modbus message does not define/contain the RUN_PERMITTED flag. (Spec)

Definition at line 234 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterRunPermittedTest  ,
ModbusMsgExceptionCTOR   
)

Check construction of the exception (essentially for full function coverage)

Definition at line 249 of file unittest_modbus_adapter_run_permitted.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testOperationModeChange   
)
  • Tests the handling of an incoming modbus message informing about changing operation mode. (Spec)

Test Sequence:

  1. Subscribe to operation modes topic.
  2. Publish modbus message informing about changing operation mode. Repeat for all possible operation modes.

Expected Results:

  1. Operation mode UNKNOWN is published.
  2. All operation modes are published in the order from above. GetOperationMode service returns expected operation mode.

Definition at line 251 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testDisconnect   
)
  • Tests the handling of an incoming modbus message informing about a disconnect. (Spec)

Test Sequence:

  1. Subscribe to operation modes topic.
  2. Publish modbus message informing about operation mode T1.
  3. Publish modbus message informing about disconnect.

Expected Results:

  1. Operation mode UNKNOWN is published.
  2. Operation mode T1 is published.
  3. Operation mode UNKNOWN is published.

Definition at line 300 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testModbusUnexpectedOperationMode   
)
  • Tests the handling of an incoming modbus message with unexpected operation mode. (Spec)

Test Sequence:

  1. Subscribe to operation modes topic.
  2. Publish modbus message with operation mode T1.
  3. Publish modbus message with an unexpected operation mode.

Expected Results:

  1. Operation mode UNKNOWN is published.
  2. Operation mode T1 is published.
  3. Operation mode UNKNOWN is published.

Definition at line 356 of file unittest_modbus_adapter_operation_mode.cpp.

prbt_hardware_support::TEST_F ( ModbusAdapterOperationModeTest  ,
testModbusIncorrectApiVersion   
)
  • Tests the handling of an incoming modbus message with incorrect api version. (Spec)

Test Sequence:

  1. Publish modbus message with operation mode T1 and correct version.
  2. Publish modbus message with operation mode T2 and incorrect version.

Expected Results:

  1. The version is T1
  2. The version is Unknown

Definition at line 406 of file unittest_modbus_adapter_operation_mode.cpp.

bool prbt_hardware_support::triggerCallbackDummy ( std_srvs::TriggerRequest &  req,
std_srvs::TriggerResponse &  resp 
)

Definition at line 43 of file integrationtest_stop1_service_missing.cpp.

template<class T >
static void prbt_hardware_support::triggerServiceCall ( T &  client)
static

Definition at line 32 of file brake_test_executor_node_service_calls.h.

void prbt_hardware_support::waitForNode ( std::string  node_name,
double  loop_frequency = 10.0 
)
inline

Blocks until a node defined by node_name comes up.

Parameters
node_name
loop_frequencyFrequency at which the system is checked for the node.

Definition at line 47 of file ros_test_helper.h.

inline ::testing::AssertionResult prbt_hardware_support::waitForNodeShutdown ( std::string  node_name,
double  timeout = 1.0,
double  loop_frequency = 10.0 
)

Blocks until a node defined by node_name can no longer be found.

Parameters
node_name
timeout
loop_frequencyFrequency at which the system is checked for the node.

Definition at line 65 of file ros_test_helper.h.

template<class T >
static bool prbt_hardware_support::writeModbusRegisterCall ( T &  modbus_service,
const uint16_t &  start_idx,
const RegCont values 
)
static

Definition at line 31 of file write_modbus_register_call.h.

Variable Documentation

const std::string prbt_hardware_support::BRAKE_TEST_DURATION_OBJECT_INDEX {"2060sub1"}
static

Definition at line 30 of file canopen_chain_node_mock.cpp.

constexpr unsigned int prbt_hardware_support::BRAKE_TEST_PERFORMED {1}
static

Definition at line 29 of file modbus_adapter_brake_test.cpp.

const std::string prbt_hardware_support::BRAKE_TEST_STATUS_OBJECT_INDEX {"2060sub3"}
static

Definition at line 32 of file canopen_chain_node_mock.cpp.

const std::string prbt_hardware_support::CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
static

Definition at line 27 of file canopen_chain_node_mock.cpp.

const std::string prbt_hardware_support::CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
static

Definition at line 31 of file system_info.cpp.

const std::string prbt_hardware_support::CANOPEN_GETOBJECT_SERVICE_NAME {"/prbt/driver/get_object"}
static

Definition at line 37 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::CANOPEN_NODES_PARAMETER_NAME {"/prbt/driver/nodes"}
static

Definition at line 32 of file system_info.cpp.

const std::string prbt_hardware_support::CANOPEN_NODES_PARAMETER_NAME {"/prbt/driver/nodes"}
static

Definition at line 39 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::CANOPEN_SETOBJECT_SERVICE_NAME {"/prbt/driver/set_object"}
static

Definition at line 28 of file canopen_chain_node_mock.cpp.

const std::string prbt_hardware_support::CANOPEN_SETOBJECT_SERVICE_NAME {"/prbt/driver/set_object"}
static

Definition at line 38 of file canopen_braketest_adapter.cpp.

constexpr unsigned int prbt_hardware_support::DEFAULT_ALLOWED_MISSED_CALCULATIONS {3}
static

Allowed number of missed calculations. If it is exceeded a Stop1 is triggered.

Definition at line 35 of file speed_observer.h.

constexpr int prbt_hardware_support::DEFAULT_QUEUE_SIZE {10}
static

Definition at line 26 of file adapter_operation_mode.cpp.

constexpr int prbt_hardware_support::DEFAULT_QUEUE_SIZE_MODBUS {1}
static

Definition at line 33 of file unittest_modbus_adapter_operation_mode.cpp.

constexpr unsigned int prbt_hardware_support::DEFAULT_RETRIES {10}
static

Definition at line 61 of file integrationtest_brake_test_required.cpp.

constexpr double prbt_hardware_support::EXPECTED_DEFAULT_SPEED_OVERRIDE {1.0}
static

Definition at line 29 of file unittest_fake_speed_override.cpp.

constexpr std::size_t prbt_hardware_support::FIRMWARE_STRING_LENGTH {40}
static

Definition at line 39 of file system_info.cpp.

const std::string prbt_hardware_support::FRAME_SPEEDS_TOPIC_NAME { "frame_speeds" }
static

Definition at line 30 of file speed_observer.cpp.

const std::string prbt_hardware_support::GET_BRAKETEST_DURATION_OBJECT {"2060sub1"}
static

Definition at line 43 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::GET_BRAKETEST_STATUS_OBJECT {"2060sub3"}
static

Definition at line 45 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::GET_FIRMWARE_VERION_OBJECT {"100A"}
static

Definition at line 35 of file system_info.cpp.

const std::string prbt_hardware_support::HALT_SERVICE_NAME {"halt"}
static

Definition at line 34 of file integrationtest_stop1_service_missing.cpp.

const std::string prbt_hardware_support::HALT_SERVICE_NAME {"halt"}
static

Definition at line 62 of file integrationtest_stop1.cpp.

const std::string prbt_hardware_support::HOLD_SERVICE_NAME {"hold"}
static

Definition at line 35 of file integrationtest_stop1_service_missing.cpp.

const std::string prbt_hardware_support::HOLD_SERVICE_NAME {"hold"}
static

Definition at line 63 of file integrationtest_stop1.cpp.

const std::string prbt_hardware_support::JOINT_STATE_TOPIC {"/joint_states"}
static

Definition at line 33 of file system_info.cpp.

const std::string prbt_hardware_support::JOINT_STATES_TOPIC_NAME {"/prbt/joint_states"}
static

Definition at line 30 of file joint_states_publisher_mock.cpp.

constexpr unsigned int prbt_hardware_support::JOINT_STATES_TOPIC_QUEUE_SIZE {1}
static

Definition at line 31 of file joint_states_publisher_mock.cpp.

constexpr const char* const prbt_hardware_support::LOCALHOST = "127.0.0.1"

Definition at line 7 of file client_tests_common.h.

constexpr int prbt_hardware_support::MODBUS_API_VERSION_FOR_TESTING {2}
static

Definition at line 44 of file unittest_modbus_adapter_run_permitted.cpp.

constexpr unsigned int prbt_hardware_support::MODBUS_API_VERSION_REQUIRED {2}
static

Definition at line 28 of file modbus_adapter_brake_test.cpp.

constexpr unsigned int prbt_hardware_support::MODBUS_API_VERSION_REQUIRED {2}
static

Definition at line 36 of file unittest_modbus_adapter_brake_test.cpp.

constexpr unsigned int prbt_hardware_support::MODBUS_API_VERSION_REQUIRED {2}
static

Definition at line 40 of file unittest_modbus_adapter_operation_mode.cpp.

constexpr uint16_t prbt_hardware_support::MODBUS_API_VERSION_VALUE {2}
static

Definition at line 37 of file integrationtest_operation_mode.cpp.

constexpr uint16_t prbt_hardware_support::MODBUS_API_VERSION_VALUE {2}
static

Definition at line 57 of file integrationtest_brake_test_required.cpp.

constexpr uint16_t prbt_hardware_support::MODBUS_API_VERSION_VALUE {2}
static

Definition at line 60 of file integrationtest_stop1.cpp.

const std::string prbt_hardware_support::MODBUS_SERVICE_NAME {"/pilz_modbus_client_node/modbus_write"}
static

Definition at line 59 of file integrationtest_brake_test_required.cpp.

const std::string prbt_hardware_support::NODE_BRAKETEST_ENABLED_PARAMETER {"braketest_required"}
static

Definition at line 40 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::OMIT_SERVICE_PARAM_NAME {"omit_service"}
static

Definition at line 38 of file integrationtest_stop1_service_missing.cpp.

const std::string prbt_hardware_support::OPERATION_MODE_CALLBACK_EVENT {"operation_mode_callback_event"}
static

Definition at line 38 of file unittest_modbus_adapter_operation_mode.cpp.

const std::string prbt_hardware_support::OPERATION_MODE_CALLBACK_EVENT {"operation_mode_callback_event"}
static

Definition at line 42 of file integrationtest_operation_mode.cpp.

constexpr int prbt_hardware_support::OPERATION_MODE_QUEUE_SIZE {1}
static

Definition at line 36 of file unittest_modbus_adapter_operation_mode.cpp.

constexpr int prbt_hardware_support::OPERATION_MODE_QUEUE_SIZE {1}
static

Definition at line 40 of file integrationtest_operation_mode.cpp.

const std::vector<uint16_t> prbt_hardware_support::OPERATION_MODES {1, 2, 3}
static

Definition at line 45 of file unittest_modbus_adapter_operation_mode.cpp.

const std::string prbt_hardware_support::PARAM_INDEX_OF_FIRST_REGISTER_TO_READ_STR {"index_of_first_register_to_read"}
static

Definition at line 31 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_CONNECTION_RETRIES {"modbus_connection_retries"}
static

Definition at line 33 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_CONNECTION_RETRY_TIMEOUT {"modbus_connection_retry_timeout"}
static

Definition at line 34 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_READ_TOPIC_NAME_STR {"modbus_read_topic_name"}
static

Definition at line 29 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_RESPONSE_TIMEOUT_STR {"modbus_response_timeout"}
static

Definition at line 28 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_SERVER_IP_STR {"modbus_server_ip"}
static

Definition at line 26 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_SERVER_PORT_STR {"modbus_server_port"}
static

Definition at line 27 of file param_names.h.

const std::string prbt_hardware_support::PARAM_MODBUS_WRITE_SERVICE_NAME_STR {"modbus_write_service_name"}
static

Definition at line 30 of file param_names.h.

const std::string prbt_hardware_support::PARAM_NUM_REGISTERS_TO_READ_STR {"num_registers_to_read"}
static

Definition at line 32 of file param_names.h.

const std::string prbt_hardware_support::READ_API_SPEC_PARAM_NAME {"read_api_spec/"}
static

Definition at line 32 of file modbus_api_spec.h.

const std::string prbt_hardware_support::RECOVER_SERVICE_NAME {"recover"}
static

Definition at line 33 of file integrationtest_stop1_service_missing.cpp.

const std::string prbt_hardware_support::RECOVER_SERVICE_NAME {"recover"}
static

Definition at line 61 of file integrationtest_stop1.cpp.

constexpr uint16_t prbt_hardware_support::REGISTER_VALUE_BRAKETEST_NOT_REQUIRED {0}
static

Definition at line 28 of file modbus_msg_brake_test_wrapper.h.

constexpr uint16_t prbt_hardware_support::REGISTER_VALUE_BRAKETEST_REQUIRED {1}
static

Definition at line 29 of file modbus_msg_brake_test_wrapper.h.

constexpr bool prbt_hardware_support::RUN_PERMITTED_ACTIVE {false}
static

Definition at line 39 of file unittest_modbus_adapter_run_permitted.cpp.

constexpr bool prbt_hardware_support::RUN_PERMITTED_CLEAR {true}
static

Definition at line 38 of file unittest_modbus_adapter_run_permitted.cpp.

const std::string prbt_hardware_support::RUN_PERMITTED_SERVICE { "run_permitted" }
static

Definition at line 31 of file speed_observer.cpp.

const std::string prbt_hardware_support::SERVICE_BRAKETEST_REQUIRED = "/prbt/brake_test_required"
static

Definition at line 58 of file integrationtest_brake_test_required.cpp.

const std::string prbt_hardware_support::SERVICE_MODBUS_WRITE = "/pilz_modbus_client_node/modbus_write"
static

Definition at line 27 of file modbus_topic_definitions.h.

const std::string prbt_hardware_support::SERVICE_NAME_GET_OPERATION_MODE = "/prbt/get_operation_mode"
static

Definition at line 24 of file adapter_operation_mode.cpp.

const std::string prbt_hardware_support::SERVICE_NAME_OPERATION_MODE = "/prbt/get_operation_mode"
static

Definition at line 34 of file unittest_modbus_adapter_operation_mode.cpp.

const std::string prbt_hardware_support::SET_START_BRAKETEST_OBJECT {"2060sub2"}
static

Definition at line 44 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::START_BRAKE_TEST_OBJECT_INDEX {"2060sub2"}
static

Definition at line 31 of file canopen_chain_node_mock.cpp.

const std::string prbt_hardware_support::STOP1_EXECUTOR_NODE_NAME {"/stop1_executor_node"}
static

Definition at line 39 of file integrationtest_stop1_service_missing.cpp.

const ModbusApiSpec prbt_hardware_support::TEST_API_SPEC
static
Initial value:
{ {modbus_api_spec::VERSION, 969},
static const std::string BRAKETEST_REQUEST

Definition at line 38 of file unittest_modbus_adapter_brake_test.cpp.

const ModbusApiSpec prbt_hardware_support::TEST_API_SPEC
static
Initial value:
{ {modbus_api_spec::VERSION, 513},
static const std::string RUN_PERMITTED

Definition at line 41 of file unittest_modbus_adapter_run_permitted.cpp.

const ModbusApiSpec prbt_hardware_support::test_api_spec
static
Initial value:
{ {modbus_api_spec::VERSION, 1},
static const std::string OPERATION_MODE

Definition at line 42 of file unittest_modbus_adapter_operation_mode.cpp.

const ModbusApiSpec prbt_hardware_support::TEST_API_WRITE_SPEC
static
const std::string prbt_hardware_support::TOPIC_MODBUS_READ = "/pilz_modbus_client_node/modbus_read"
static

Definition at line 26 of file modbus_topic_definitions.h.

const std::string prbt_hardware_support::TOPIC_OPERATION_MODE = "/prbt/operation_mode"
static

Definition at line 23 of file adapter_operation_mode.cpp.

const std::string prbt_hardware_support::TOPIC_OPERATION_MODE {"/prbt/operation_mode"}
static

Definition at line 35 of file unittest_modbus_adapter_operation_mode.cpp.

const std::string prbt_hardware_support::TOPIC_OPERATION_MODE {"/prbt/operation_mode"}
static

Definition at line 39 of file integrationtest_operation_mode.cpp.

const std::string prbt_hardware_support::TRIGGER_BRAKETEST_SERVICE_NAME {"/trigger_braketest"}
static

Definition at line 36 of file canopen_braketest_adapter.cpp.

const std::string prbt_hardware_support::UNHOLD_SERVICE_NAME {"unhold"}
static

Definition at line 36 of file integrationtest_stop1_service_missing.cpp.

const std::string prbt_hardware_support::UNHOLD_SERVICE_NAME {"unhold"}
static

Definition at line 64 of file integrationtest_stop1.cpp.

constexpr double prbt_hardware_support::WAIT_FOR_NODE_SLEEPTIME_S {5.0}
static

Definition at line 41 of file integrationtest_stop1_service_missing.cpp.

constexpr double prbt_hardware_support::WAIT_FOR_SERVICE_TIMEOUT_S {5.0}
static

Definition at line 41 of file canopen_braketest_adapter.cpp.



prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:18