network_configuration.cpp
Go to the documentation of this file.
1 /* Copyright (c) 2023, Beamagine
2 
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  - Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10  - Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation and/or
12  other materials provided with the distribution.
13  - Neither the name of copyright holders nor the names of its contributors may be
14  used to endorse or promote products derived from this software without specific
15  prior written permission.
16 
17  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY
18  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
19  MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
20  COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
21  EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
23  HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
24  TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
25  EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <iostream>
29 #include <ros/ros.h>
30 
31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/NetworkConfig.h"
33 
34 #include <libL3Cam.h>
35 #include <beamagine.h>
36 #include <beamErrors.h>
37 
38 #include "l3cam_ros/GetNetworkConfiguration.h"
39 #include "l3cam_ros/ChangeNetworkConfiguration.h"
40 
41 #include "l3cam_ros/SensorDisconnected.h"
42 
43 #include "l3cam_ros_utils.hpp"
44 
45 namespace l3cam_ros
46 {
48  {
49  public:
50  explicit NetworkConfiguration() : ros::NodeHandle("~")
51  {
52  // Create service clients
53  client_get_ = serviceClient<l3cam_ros::GetNetworkConfiguration>("/L3Cam/l3cam_ros_node/get_network_configuration");
54  client_change_ = serviceClient<l3cam_ros::ChangeNetworkConfiguration>("/L3Cam/l3cam_ros_node/change_network_configuration");
55 
56  // Create service server
58 
59  loadParam("timeout_secs", timeout_secs_, 60);
60 
61  m_default_configured = false;
62  m_shutdown_requested = false;
63  }
64 
65  void spin()
66  {
67  while (ros::ok() && !m_shutdown_requested)
68  {
69  ros::spinOnce();
70  ros::Duration(0.1).sleep();
71  }
72 
73  ros::shutdown();
74  }
75 
77  {
78  // Check if service is available
79  ros::Duration timeout_duration(timeout_secs_);
80  if (!client_get_.waitForExistence(timeout_duration))
81  {
82  ROS_ERROR_STREAM(this->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
84  }
85 
86  int error = L3CAM_OK;
88  {
89  error = srv_get_.response.error;
90 
91  if (!error)
92  {
93  ip_address_ = srv_get_.response.ip_address;
94  netmask_ = srv_get_.response.netmask;
95  gateway_ = srv_get_.response.gateway;
96  dhcp_ = false;
97 
99  }
100  else
101  {
102  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while getting network configuration in " << __func__ << ": " << getErrorDescription(error));
103  return error;
104  }
105  }
106  else
107  {
108  ROS_ERROR_STREAM(this->getNamespace() << " error: Failed to call service get_network_configuration");
110  }
111 
112  return error;
113  }
114 
116  l3cam_ros::GetNetworkConfiguration srv_get_;
117 
118  private:
120  {
121  // Dynamic reconfigure callback
122  server_.setCallback(std::bind(&NetworkConfiguration::parametersCallback, this, std::placeholders::_1, std::placeholders::_2));
123  }
124 
125  template <typename T>
126  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
127  {
128  std::string full_param_name;
129 
130  if (searchParam(param_name, full_param_name))
131  {
132  if(!getParam(full_param_name, param_var))
133  {
134  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
135  }
136  }
137  else
138  {
139  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
140  param_var = default_val;
141  }
142  }
143 
144  void parametersCallback(l3cam_ros::NetworkConfig &config, uint32_t level)
145  {
146  int error = L3CAM_OK;
147 
149  {
150  config.ip_address = ip_address_;
151  config.netmask = netmask_;
152  config.gateway = gateway_;
153  config.dhcp = dhcp_;
154 
155  m_default_configured = true;
156  }
157  else
158  {
159  error = callNetwork(config);
160  }
161 
162  if (error)
163  {
164  ROS_ERROR_STREAM(this->getNamespace() << " error " << error << " while changing parameter: " << getErrorDescription(error));
165  }
166  }
167 
168  // Sensor calls
169  int callNetwork(l3cam_ros::NetworkConfig &config)
170  {
171  int error = L3CAM_OK;
172 
173  srv_change_.request.ip_address = config.ip_address;
174  srv_change_.request.netmask = config.netmask;
175  srv_change_.request.gateway = config.gateway;
176  srv_change_.request.enable_dhcp = config.dhcp;
178  {
179  error = srv_change_.response.error;
180  if (!error)
181  {
182  // Parameter changed successfully, save value
183  ip_address_ = config.ip_address;
184  netmask_ = config.netmask;
185  gateway_ = config.gateway;
186  dhcp_ = config.dhcp;
187  }
188  else
189  {
190  // Parameter could not be changed, reset parameter to value before change
191  config.ip_address = ip_address_;
192  config.netmask = netmask_;
193  config.gateway = gateway_;
194  config.dhcp = dhcp_;
195  }
196  }
197  else
198  {
199  // Service could not be called, reset parameter to value before change
200  config.ip_address = ip_address_;
201  config.netmask = netmask_;
202  config.gateway = gateway_;
203  config.dhcp = dhcp_;
205  }
206 
207  return error;
208  }
209 
210  bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
211  {
212  ROS_BMG_UNUSED(res);
213  if (req.code == 0)
214  {
215  ROS_INFO_STREAM("Exiting " << this->getNamespace() << " cleanly.");
216  }
217  else
218  {
219  ROS_WARN_STREAM("Exiting " << this->getNamespace() << ". Sensor got disconnected with error " << req.code << ": " << getErrorDescription(req.code));
220  }
221 
222  m_shutdown_requested = true;
223  return true;
224  }
225 
226  dynamic_reconfigure::Server<l3cam_ros::NetworkConfig> server_;
227 
229  l3cam_ros::ChangeNetworkConfiguration srv_change_;
230 
232 
233  std::string ip_address_;
234  std::string netmask_;
235  std::string gateway_;
236  bool dhcp_;
237 
239 
242 
243  }; // class NetworkConfiguration
244 
245 } // namespace l3cam_ros
246 
247 int main(int argc, char **argv)
248 {
249  ros::init(argc, argv, "network_configuration");
250 
252 
253  // Shutdown if error returned
254  int error = node->getNetworkConfiguration();
255  if (error)
256  {
257  return error;
258  }
259 
260  ROS_INFO("Network configuration is available");
261 
262  node->spin();
263 
264  ros::shutdown();
265  return 0;
266 }
l3cam_ros::NetworkConfiguration::server_
dynamic_reconfigure::Server< l3cam_ros::NetworkConfig > server_
Definition: network_configuration.cpp:226
l3cam_ros::NetworkConfiguration::m_default_configured
bool m_default_configured
Definition: network_configuration.cpp:240
ros::ServiceClient::waitForExistence
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
l3cam_ros::NetworkConfiguration::client_change_
ros::ServiceClient client_change_
Definition: network_configuration.cpp:228
l3cam_ros::NetworkConfiguration::parametersCallback
void parametersCallback(l3cam_ros::NetworkConfig &config, uint32_t level)
Definition: network_configuration.cpp:144
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
l3cam_ros::NetworkConfiguration::spin
void spin()
Definition: network_configuration.cpp:65
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
l3cam_ros::NetworkConfiguration::timeout_secs_
int timeout_secs_
Definition: network_configuration.cpp:238
ros
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
ros::spinOnce
ROSCPP_DECL void spinOnce()
l3cam_ros::NetworkConfiguration
Definition: network_configuration.cpp:47
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ROS_BMG_UNUSED
#define ROS_BMG_UNUSED(x)
Definition: l3cam_ros_utils.hpp:32
ros::ok
ROSCPP_DECL bool ok()
l3cam_ros::NetworkConfiguration::netmask_
std::string netmask_
Definition: network_configuration.cpp:234
ros::ServiceServer
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
l3cam_ros::NetworkConfiguration::NetworkConfiguration
NetworkConfiguration()
Definition: network_configuration.cpp:50
l3cam_ros::L3Cam::getNetworkConfiguration
bool getNetworkConfiguration(l3cam_ros::GetNetworkConfiguration::Request &req, l3cam_ros::GetNetworkConfiguration::Response &res)
Definition: l3cam_ros_node.cpp:1146
l3cam_ros_utils.hpp
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
ros::ServiceClient
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
l3cam_ros::NetworkConfiguration::gateway_
std::string gateway_
Definition: network_configuration.cpp:235
ros::NodeHandle::NodeHandle
NodeHandle(const NodeHandle &parent, const std::string &ns)
main
int main(int argc, char **argv)
Definition: network_configuration.cpp:247
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
l3cam_ros::NetworkConfiguration::client_get_
ros::ServiceClient client_get_
Definition: network_configuration.cpp:115
l3cam_ros::NetworkConfiguration::setDynamicReconfigure
void setDynamicReconfigure()
Definition: network_configuration.cpp:119
l3cam_ros::NetworkConfiguration::srv_get_
l3cam_ros::GetNetworkConfiguration srv_get_
Definition: network_configuration.cpp:116
l3cam_ros::NetworkConfiguration::dhcp_
bool dhcp_
Definition: network_configuration.cpp:236
l3cam_ros::NetworkConfiguration::callNetwork
int callNetwork(l3cam_ros::NetworkConfig &config)
Definition: network_configuration.cpp:169
l3cam_ros::NetworkConfiguration::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: network_configuration.cpp:126
l3cam_ros::NetworkConfiguration::getNetworkConfiguration
int getNetworkConfiguration()
Definition: network_configuration.cpp:76
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
l3cam_ros::NetworkConfiguration::m_shutdown_requested
bool m_shutdown_requested
Definition: network_configuration.cpp:241
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::NetworkConfiguration::ip_address_
std::string ip_address_
Definition: network_configuration.cpp:233
ros::Duration::sleep
bool sleep() const
l3cam_ros::NetworkConfiguration::srv_sensor_disconnected_
ros::ServiceServer srv_sensor_disconnected_
Definition: network_configuration.cpp:231
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ROS_INFO
#define ROS_INFO(...)
l3cam_ros::NetworkConfiguration::sensorDisconnectedCallback
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
Definition: network_configuration.cpp:210
ros::Duration
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
ros::NodeHandle
l3cam_ros::NetworkConfiguration::srv_change_
l3cam_ros::ChangeNetworkConfiguration srv_change_
Definition: network_configuration.cpp:229


l3cam_ros
Author(s): Beamagine
autogenerated on Wed May 28 2025 02:53:15