muse_v2.cpp
Go to the documentation of this file.
7 
8 int main(int argc, char** argv)
9 {
10  ros::init(argc, argv, "muse");
11 
13 
14  muse_v2_driver::MuseV2 muse_v2(n);
15 
16  ROS_INFO("Port name: %s", muse_v2.params.port_name);
17  ROS_INFO("Baudrate: %d", muse_v2.params.baudrate);
18 
19  int publisher_queue_size;
20 
21  if (!n.getParam("publisher_queue_size", publisher_queue_size))
22  ROS_WARN("No publisher_queue_size parameter found on server. Use default one.");
23 
24  muse_v2_driver::Stream stream(n, publisher_queue_size);
29 
30  std::vector<ros::Subscriber> sub_vect;
31 
32  ros::Subscriber stream_sub = n.subscribe<muse_v2_driver::Transmission>("start_transmission", 1, boost::bind(&muse_v2_driver::Stream::StreamRawData, &stream, _1, &muse_v2));
33  sub_vect.push_back(stream_sub);
34 
35  ros::ServiceServer stop_transmission_srv = n.advertiseService<muse_v2_driver::StopTransmission::Request, muse_v2_driver::StopTransmission::Response>
36  ("stop_transmission", boost::bind(&muse_v2_driver::MuseV2::stopTransmission, &muse_v2, _1, _2, &muse_v2));
37 
38  ros::ServiceServer shutdown_srv = n.advertiseService<muse_v2_driver::Shutdown::Request, muse_v2_driver::Shutdown::Response>
39  ("shutdown", boost::bind(&muse_v2_driver::MuseV2::shutdown, &muse_v2, _1, _2, &muse_v2, sub_vect));
40 
41  ros::ServiceServer battery_srv = n.advertiseService<muse_v2_driver::Battery::Request, muse_v2_driver::Battery::Response>
42  ("battery", boost::bind(&muse_v2_driver::Miscellaneous::getBattery, &misc, _1, _2, &muse_v2));
43 
44  ros::ServiceServer get_config_params_srv = n.advertiseService<muse_v2_driver::GetConfigurationParams::Request, muse_v2_driver::GetConfigurationParams::Response>
45  ("get_configuration_params", boost::bind(&muse_v2_driver::Configuration::getConfigurationParams, &config, _1, _2, &muse_v2));
46 
47  ros::ServiceServer set_config_params_srv = n.advertiseService<muse_v2_driver::SetConfigurationParams::Request, muse_v2_driver::SetConfigurationParams::Response>
48  ("set_configuration_params", boost::bind(&muse_v2_driver::Configuration::setConfigurationParams, &config, _1, _2, &muse_v2));
49 
50  ros::ServiceServer get_calib_params_srv = n.advertiseService<muse_v2_driver::GetCalibrationParams::Request, muse_v2_driver::GetCalibrationParams::Response>
51  ("get_calibration_params", boost::bind(&muse_v2_driver::Calibration::getCalibrationParams, &calib, _1, _2, &muse_v2));
52 
53  ros::ServiceServer logger_srv = n.advertiseService<muse_v2_driver::MemoryManagement::Request, muse_v2_driver::MemoryManagement::Response>
54  ("logger", boost::bind(&muse_v2_driver::Memory::logger, &mem, _1, _2, &muse_v2));
55 
56 
57  ROS_INFO("Muse V2 ready.");
58 
59  ros::spin();
60 
61  return 0;
62 
63 }
muse_v2_driver::Configuration::getConfigurationParams
bool getConfigurationParams(GetConfigurationParams::Request &req, GetConfigurationParams::Response &res, MuseV2 *muse_v2)
Definition: Configuration.cpp:27
muse_v2_driver::Miscellaneous
Definition: Miscellaneous.h:9
muse_v2_driver::Miscellaneous::getBattery
bool getBattery(Battery::Request &req, Battery::Response &res, MuseV2 *muse_v2)
Definition: Miscellaneous.cpp:8
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
Miscellaneous.h
main
int main(int argc, char **argv)
Definition: muse_v2.cpp:8
muse_v2_driver::Stream::StreamRawData
void StreamRawData(const Transmission::ConstPtr &msg, MuseV2 *muse_v2)
Definition: Stream.cpp:35
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
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
ros::ServiceServer
muse_v2_driver::MuseV2::Params::port_name
string port_name
Definition: MuseV2.h:28
MuseV2.h
muse_v2_driver::Calibration::getCalibrationParams
bool getCalibrationParams(GetCalibrationParams::Request &req, GetCalibrationParams::Response &res, MuseV2 *muse_v2)
Definition: Calibration.cpp:11
muse_v2_driver::Memory::logger
bool logger(MemoryManagement::Request &req, MemoryManagement::Response &res, MuseV2 *muse_v2)
Definition: Memory.cpp:13
ROS_WARN
#define ROS_WARN(...)
muse_v2_driver::MuseV2::params
Params params
Definition: MuseV2.h:40
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
muse_v2_driver::Stream
Definition: Stream.h:18
muse_v2_driver::Calibration
Definition: Calibration.h:11
muse_v2_driver::Memory
Definition: Memory.h:21
Memory.h
muse_v2_driver::MuseV2
Definition: MuseV2.h:21
Calibration.h
ros::spin
ROSCPP_DECL void spin()
muse_v2_driver::MuseV2::Params::baudrate
uint32_t baudrate
Definition: MuseV2.h:29
Stream.h
ROS_INFO
#define ROS_INFO(...)
muse_v2_driver::Configuration
Definition: Configuration.h:10
Configuration.h
ros::NodeHandle
ros::Subscriber
muse_v2_driver::Configuration::setConfigurationParams
bool setConfigurationParams(SetConfigurationParams::Request &req, SetConfigurationParams::Response &res, MuseV2 *muse_v2)
Definition: Configuration.cpp:109


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