1 #ifndef KINEMATICS_RV2AJ_DRIVER_HPP 2 #define KINEMATICS_RV2AJ_DRIVER_HPP 5 #include "HLR/RV2AJDriverClear.h" 6 #include "HLR/RV2AJDriverContinue.h" 7 #include "HLR/RV2AJDriverPause.h" 8 #include "HLR/RV2AJDriverQueueAdd.h" 9 #include "HLR/RV2AJDriverQueueCount.h" 10 #include "std_msgs/String.h" 13 #include <condition_variable> 37 Driver(
bool simulation,
const std::optional<std::string>& serial_path);
74 bool cont(HLR::RV2AJDriverContinue::Request& req,
75 HLR::RV2AJDriverContinue::Response& res);
83 bool pause(HLR::RV2AJDriverPause::Request& req,
84 HLR::RV2AJDriverPause::Response& res);
92 bool clear(HLR::RV2AJDriverClear::Request& req,
93 HLR::RV2AJDriverClear::Response& res);
101 bool queue_count(HLR::RV2AJDriverQueueCount::Request& req,
102 HLR::RV2AJDriverQueueCount::Response& res);
110 bool queue_add(HLR::RV2AJDriverQueueAdd::Request& req,
111 HLR::RV2AJDriverQueueAdd::Response& res);
126 std::array<std::string, 3> to_mb4()
const;
165 bool tx(
const Command& cmd);
172 void tx(
const std::string& mb4);
184 void rx_sub_callback(
const std_msgs::String::ConstPtr& msg);
193 std::size_t device_count = 0;
199 ros::Publisher tx_pub;
202 bool tx_abort =
false;
205 std::mutex tx_abort_m;
208 bool rx_block =
true;
211 std::mutex rx_block_m;
214 std::condition_variable rx_block_cv;
217 ros::Subscriber rx_sub;
220 ros::ServiceServer srv_continue;
223 ros::ServiceServer srv_pause;
226 ros::ServiceServer srv_clear;
229 ros::ServiceServer srv_queue_count;
232 ros::ServiceServer srv_queue_add;
238 State worker_state = State::cont;
241 std::mutex worker_state_m;
244 std::queue<Command> commands;
247 std::mutex commands_m;
250 std::condition_variable commands_cv;
253 std::thread worker_reply;
256 State worker_reply_state = State::cont;
259 std::mutex worker_reply_state_m;
262 std::queue<std::string> replies;
265 std::mutex replies_m;
268 std::condition_variable replies_cv;
Driver for the Mitsubishi RV2-AJ.
Definition: Driver.hpp:28
bool queue_add(HLR::RV2AJDriverQueueAdd::Request &req, HLR::RV2AJDriverQueueAdd::Response &res)
Add requested command to the queue if compliant.
virtual ~Driver()
Destructor.
OO wrapper around POSIX serial devices.
Definition: Serial.hpp:13
bool pause(HLR::RV2AJDriverPause::Request &req, HLR::RV2AJDriverPause::Response &res)
Pause processing events in queue.
bool clear(HLR::RV2AJDriverClear::Request &req, HLR::RV2AJDriverClear::Response &res)
Clears all to-be processed events in queue.
bool cont(HLR::RV2AJDriverContinue::Request &req, HLR::RV2AJDriverContinue::Response &res)
Continue processing events in queue.
bool queue_count(HLR::RV2AJDriverQueueCount::Request &req, HLR::RV2AJDriverQueueCount::Response &res)
Returns the number of elements currently inside the queue.
Driver(bool simulation, const std::optional< std::string > &serial_path)
Constructor.
Driver & operator=(const Driver &d)=delete
Copy assignment operator, deleted.