27 #include <prbt_hardware_support/WriteModbusRegister.h> 40 int main(
int argc,
char **argv)
42 ros::init(argc, argv,
"modbus_adapter_brake_test");
53 using std::placeholders::_1;
54 using std::placeholders::_2;
56 std::bind(writeModbusRegisterCall<ros::ServiceClient>, modbus_write_client, _1, _2),
57 read_api_spec, write_api_spec);
int main(int argc, char **argv)
Starts a modbus brake test announcer and runs it until a failure occurs.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
static const std::string MODBUS_WRITE_SERVICE_NAME
static const std::string SERVICE_SEND_BRAKE_TEST_RESULT
ROSCPP_DECL void spin(Spinner &spinner)
bool sendBrakeTestResult(SendBrakeTestResult::Request &req, SendBrakeTestResult::Response &res)
Sends the brake test result data to the modbus client.
An abstraction of a series of filters which ensures that only Modbus messages with different timestam...
static const std::string API_SPEC_WRITE_PARAM_NAME("write_api_spec/")
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
#define ROS_DEBUG_STREAM(args)
bool isBrakeTestRequired(IsBrakeTestRequired::Request &, IsBrakeTestRequired::Response &res)
Stores the brake test required flag and initializes the brake test service, the first time the functi...
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus message arrives.
static const std::string SERVICE_NAME_IS_BRAKE_TEST_REQUIRED
Listens to the modbus_read topic and publishes a message informing about a required brake test...
Specifies the meaning of the holding registers.