28 #include "novatel_oem7_msgs/Oem7AbasciiCmd.h" 38 bool isPrefix(
const std::string& prefix,
const std::string& str)
40 auto const diff_pos = std::mismatch(prefix.begin(), prefix.end(), str.begin());
41 return diff_pos.first == prefix.end();
66 << __DATE__ <<
" " << __TIME__);
80 std::vector<std::string> receiver_init_commands;
82 for(
const auto&
cmd : receiver_init_commands)
89 std::vector<std::string> receiver_ext_init_commands;
91 for(
const auto&
cmd : receiver_ext_init_commands)
107 static const std::string CMD_PAUSE(
"!PAUSE");
108 if(isPrefix(CMD_PAUSE, cmd))
110 std::stringstream ss(cmd);
114 int pause_period_sec = 0;
115 if(std::stringstream(token) >> pause_period_sec)
117 ROS_INFO_STREAM(
"Sleeping for " << pause_period_sec <<
" seconds....");
141 novatel_oem7_msgs::Oem7AbasciiCmd oem7_cmd;
142 oem7_cmd.request.cmd = cmd;
144 if(client_.
call(oem7_cmd))
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
#define NODELET_INFO_STREAM(...)
const std::string & getName() const
bool call(MReq &req, MRes &res)
void issueConfigCmd(const std::string &cmd)
#define NODELET_ERROR_STREAM(...)
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
ros::ServiceClient client_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
bool executeInternalCommand(const std::string &cmd)
ros::NodeHandle & getNodeHandle() const
#define NODELET_DEBUG_STREAM(...)
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
ros::Timer serviceCbTimer_
#define ROS_ERROR_STREAM(args)
void serviceLoopCb(const ros::TimerEvent &event)