modbus_adapter_brake_test_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <functional>
19 
20 #include <ros/ros.h>
21 
23 
27 #include <prbt_hardware_support/WriteModbusRegister.h>
29 
30 static const std::string API_SPEC_WRITE_PARAM_NAME("write_api_spec/");
31 static const std::string SERVICE_NAME_IS_BRAKE_TEST_REQUIRED = "/prbt/brake_test_required";
32 static const std::string SERVICE_SEND_BRAKE_TEST_RESULT = "/prbt/send_brake_test_result";
33 static const std::string MODBUS_WRITE_SERVICE_NAME{ "/pilz_modbus_client_node/modbus_write" };
34 
35 using namespace prbt_hardware_support;
36 
40 int main(int argc, char** argv)
41 {
42  ros::init(argc, argv, "modbus_adapter_brake_test");
43  ros::NodeHandle nh{};
44  ros::NodeHandle pnh{ "~" };
45 
46  ModbusApiSpec read_api_spec(nh);
47  ModbusApiSpec write_api_spec(nh, API_SPEC_WRITE_PARAM_NAME);
48 
50  ROS_DEBUG_STREAM("Done waiting for service: " << MODBUS_WRITE_SERVICE_NAME);
51  ros::ServiceClient modbus_write_client = pnh.serviceClient<WriteModbusRegister>(MODBUS_WRITE_SERVICE_NAME);
52 
53  using std::placeholders::_1;
54  using std::placeholders::_2;
55  ModbusAdapterBrakeTest adapter_brake_test(
56  std::bind(writeModbusRegisterCall<ros::ServiceClient>, modbus_write_client, _1, _2), read_api_spec,
57  write_api_spec);
58 
59  FilterPipeline filter_pipeline(pnh, std::bind(&ModbusAdapterBrakeTest::modbusMsgCallback, &adapter_brake_test, _1));
60 
61  ros::ServiceServer is_brake_test_required_server = pnh.advertiseService(
63 
64  ros::ServiceServer send_brake_test_result = pnh.advertiseService(
66 
67  ros::spin();
68 
69  return EXIT_FAILURE;
70 }
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
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/")
bool isBrakeTestRequired(pilz_msgs::IsBrakeTestRequired::Request &, pilz_msgs::IsBrakeTestRequired::Response &res)
Stores the brake test required flag and initializes the brake test service, the first time the functi...
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
ROSCPP_DECL void spin()
#define ROS_DEBUG_STREAM(args)
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.


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34