28 #include <std_srvs/SetBool.h> 37 std_srvs::SetBool srv;
38 srv.request.data = run_permitted;
39 if (!run_permitted_service.
call(srv))
44 if (!srv.response.success)
51 int main(
int argc,
char **argv)
53 ros::init(argc, argv,
"modbus_adapter_run_permitted");
56 using std::placeholders::_1;
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
void modbusMsgCallback(const ModbusMsgInStampedConstPtr &msg_raw)
Called whenever a new modbus messages arrives.
ROSCPP_DECL void spin(Spinner &spinner)
static void sendRunPermittedUpdate(ros::ServiceClient &run_permitted_service, const bool run_permitted)
An abstraction of a series of filters which ensures that only Modbus messages with different timestam...
static const std::string RUN_PERMITTED_SERVICE_NAME
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
Listens to the modbus_read topic and reacts to updated RUN_PERMITTED states.
int main(int argc, char **argv)
#define ROS_ERROR_STREAM(args)
Specifies the meaning of the holding registers.