MuseV2.cpp
Go to the documentation of this file.
2 
4 
5  if (!node.getParam("frame_id", params.frame_id))
6  ROS_WARN("No frame_id parameter found on server. Use default one.");
7 
8  if (!node.getParam("port_name", params.port_name))
9  ROS_WARN("No port_name parameter found on server. Use default one.");
10 
11  int temp_baudrate;
12  if (!node.getParam("baudrate", temp_baudrate))
13  ROS_WARN("No baudrate parameter found on server. Use default one.");
14  else
15  params.baudrate = (uint32_t)temp_baudrate;
16 
17  int temp_timeout;
18  if (!node.getParam("timeout", temp_timeout))
19  ROS_WARN("No timeout parameter found on server. Use default one.");
20  else
21  params.timeout = (Timeout)(temp_timeout);
22 }
23 
24 bool muse_v2_driver::MuseV2::stopTransmission(StopTransmission::Request& req, StopTransmission::Response& res, MuseV2* muse_v2)
25 {
26  ROS_INFO("request: stop_transmission=%s", req.stop_transmission ? "true" : "false");
27 
28  if (req.stop_transmission) {
29  muse_v2->serial->stopTransmission();
30  res.transmission_stopped = true;
31  }
32 
33  return res.transmission_stopped;
34 }
35 
36 bool muse_v2_driver::MuseV2::shutdown(Shutdown::Request& req, Shutdown::Response& res, MuseV2* muse_v2, std::vector<ros::Subscriber>& sub_vect)
37 {
38  ROS_INFO("request: shutdown=%s", req.shutdown ? "true" : "false");
39 
40  if (req.shutdown) {
41  for (auto& s : sub_vect)
42  s.shutdown();
43  muse_v2->serial->shutdown();
44  res.off = true;
45  ros::shutdown();
46  }
47 
48  return res.off;
49 }
50 
51 bool muse_v2_driver::MuseV2::disconnect(Disconnect::Request& req, Disconnect::Response& res, MuseV2* muse_v2, std::vector<ros::Subscriber>& sub_vect)
52 {
53  ROS_INFO("request: disconnect=%s", req.disconnect ? "true" : "false");
54 
55  if (req.disconnect) {
56  for (auto& s : sub_vect)
57  s.shutdown();
58 
59  muse_v2->serial->disconnect();
60  res.disconnected = true;
61  }
62 
63  return res.disconnected;
64 }
muse_v2_driver::MuseV2::Params::frame_id
string frame_id
Definition: MuseV2.h:27
s
XmlRpcServer s
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros::shutdown
ROSCPP_DECL void shutdown()
muse_v2_driver::MuseV2::stopTransmission
bool stopTransmission(StopTransmission::Request &req, StopTransmission::Response &res, MuseV2 *muse_v2)
Definition: MuseV2.cpp:24
muse_v2_driver::MuseV2::shutdown
bool shutdown(Shutdown::Request &req, Shutdown::Response &res, MuseV2 *muse_v2, std::vector< ros::Subscriber > &sub_vect)
Definition: MuseV2.cpp:36
muse_v2_driver::MuseV2::Params::port_name
string port_name
Definition: MuseV2.h:28
muse_v2_driver::MuseV2::disconnect
bool disconnect(Disconnect::Request &req, Disconnect::Response &res, MuseV2 *muse_v2, std::vector< ros::Subscriber > &sub_vect)
Definition: MuseV2.cpp:51
MuseV2.h
ROS_WARN
#define ROS_WARN(...)
muse_v2_driver::MuseV2::params
Params params
Definition: MuseV2.h:40
muse_v2_driver::MuseV2::setupParams
void setupParams(ros::NodeHandle &node)
Definition: MuseV2.cpp:3
muse_v2_driver::MuseV2::Params::timeout
Timeout timeout
Definition: MuseV2.h:30
muse_v2_driver::MuseV2
Definition: MuseV2.h:21
muse_v2_driver::MuseV2::Params::baudrate
uint32_t baudrate
Definition: MuseV2.h:29
ROS_INFO
#define ROS_INFO(...)
muse_v2_driver::MuseV2::serial
MuseV2_SerialConnection * serial
Definition: MuseV2.h:41
ros::NodeHandle


muse_v2_driver
Author(s): Elisa Tosello , Roberto Bortoletto
autogenerated on Thu Jan 20 2022 03:24:53