oem7_config_nodelet.cpp
Go to the documentation of this file.
1 //
3 // Copyright (c) 2020 NovAtel Inc.
4 //
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 //
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 //
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 //
24 
25 #include <ros/ros.h>
26 #include <nodelet/nodelet.h>
27 
28 #include "novatel_oem7_msgs/Oem7AbasciiCmd.h"
29 
30 #include <algorithm>
31 
32 namespace
33 {
34 
38  bool isPrefix(const std::string& prefix, const std::string& str)
39  {
40  auto const diff_pos = std::mismatch(prefix.begin(), prefix.end(), str.begin());
41  return diff_pos.first == prefix.end();
42  }
43 
44 }
45 
46 namespace novatel_oem7_driver
47 {
54  {
58  public:
59 
63  void onInit()
64  {
65  NODELET_INFO_STREAM(getName() << ": Oem7ConfigNodelet v." << novatel_oem7_driver_VERSION << "; "
66  << __DATE__ << " " << __TIME__);
67 
68  client_ = getNodeHandle().serviceClient<novatel_oem7_msgs::Oem7AbasciiCmd>("Oem7Cmd");
69 
71  }
72 
76  void serviceLoopCb(const ros::TimerEvent& event)
77  {
79 
80  std::vector<std::string> receiver_init_commands;
81  getNodeHandle().getParam("receiver_init_commands", receiver_init_commands);
82  for(const auto& cmd : receiver_init_commands)
83  {
85  }
86 
87  NODELET_INFO_STREAM("Oem7 extended initialization commands:");
88 
89  std::vector<std::string> receiver_ext_init_commands;
90  getNodeHandle().getParam("receiver_ext_init_commands", receiver_ext_init_commands);
91  for(const auto& cmd : receiver_ext_init_commands)
92  {
94  }
95 
96  NODELET_INFO_STREAM("Oem7 configuration completed.");
97  client_.shutdown();
98  }
99 
105  bool executeInternalCommand(const std::string& cmd)
106  {
107  static const std::string CMD_PAUSE("!PAUSE");
108  if(isPrefix(CMD_PAUSE, cmd))
109  {
110  std::stringstream ss(cmd);
111  std::string token;
112  ss >> token; // Prefix
113  ss >> token; // Period
114  int pause_period_sec = 0;
115  if(std::stringstream(token) >> pause_period_sec)
116  {
117  ROS_INFO_STREAM("Sleeping for " << pause_period_sec << " seconds....");
118  ros::Duration(pause_period_sec).sleep();
119  ROS_INFO_STREAM("... done sleeping.");
120  }
121  else
122  {
123  ROS_ERROR_STREAM("Invalid Driver command syntax: '" << cmd << "'");
124  }
125 
126  return true;
127  }
128  else // Not a recognized internal command
129  {
130  return false;
131  }
132  }
133 
137  void issueConfigCmd(const std::string& cmd )
138  {
140  {
141  novatel_oem7_msgs::Oem7AbasciiCmd oem7_cmd;
142  oem7_cmd.request.cmd = cmd;
143 
144  if(client_.call(oem7_cmd)) // BLOCKS with no timeout.
145  {
146  NODELET_DEBUG_STREAM("Config: '" << cmd << "' : Rsp: '" << oem7_cmd.response.rsp << "'");
147  }
148  else
149  {
150  NODELET_ERROR_STREAM("Config '" << cmd << "' not executed.");
151  }
152  }
153  }
154  };
155 }
156 
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
novatel_oem7_driver::Oem7ConfigNodelet::executeInternalCommand
bool executeInternalCommand(const std::string &cmd)
Definition: oem7_config_nodelet.cpp:105
novatel_oem7_driver::Oem7ConfigNodelet::issueConfigCmd
void issueConfigCmd(const std::string &cmd)
Definition: oem7_config_nodelet.cpp:137
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
novatel_oem7_driver::Oem7ConfigNodelet::serviceCbTimer_
ros::Timer serviceCbTimer_
Definition: oem7_config_nodelet.cpp:55
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
class_list_macros.h
novatel_oem7_driver::Oem7ConfigNodelet::onInit
void onInit()
Definition: oem7_config_nodelet.cpp:63
NODELET_ERROR_STREAM
#define NODELET_ERROR_STREAM(...)
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(novatel_oem7_driver::Oem7ConfigNodelet, nodelet::Nodelet)
novatel_oem7_driver::Oem7ConfigNodelet::serviceLoopCb
void serviceLoopCb(const ros::TimerEvent &event)
Definition: oem7_config_nodelet.cpp:76
ros::ServiceClient::shutdown
void shutdown()
ros::ServiceClient
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
nodelet::Nodelet
nodelet.h
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
NODELET_DEBUG_STREAM
#define NODELET_DEBUG_STREAM(...)
novatel_oem7_driver::Oem7ConfigNodelet::client_
ros::ServiceClient client_
Definition: oem7_config_nodelet.cpp:56
nodelet::Nodelet::getName
const std::string & getName() const
ros::Duration::sleep
bool sleep() const
novatel_oem7_driver::Oem7ConfigNodelet
Definition: oem7_config_nodelet.cpp:53
cmd
string cmd
NODELET_INFO_STREAM
#define NODELET_INFO_STREAM(...)
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
novatel_oem7_driver
Definition: oem7_imu.hpp:25


novatel_oem7_driver
Author(s):
autogenerated on Sat Feb 3 2024 03:51:34