Go to the documentation of this file.
31 #include <dynamic_reconfigure/server.h>
32 #include "l3cam_ros/NetworkConfig.h"
35 #include <beamagine.h>
36 #include <beamErrors.h>
38 #include "l3cam_ros/GetNetworkConfiguration.h"
39 #include "l3cam_ros/ChangeNetworkConfiguration.h"
41 #include "l3cam_ros/SensorDisconnected.h"
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");
125 template <
typename T>
126 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
128 std::string full_param_name;
132 if(!
getParam(full_param_name, param_var))
140 param_var = default_val;
146 int error = L3CAM_OK;
171 int error = L3CAM_OK;
173 srv_change_.request.ip_address = config.ip_address;
226 dynamic_reconfigure::Server<l3cam_ros::NetworkConfig>
server_;
247 int main(
int argc,
char **argv)
249 ros::init(argc, argv,
"network_configuration");
260 ROS_INFO(
"Network configuration is available");
dynamic_reconfigure::Server< l3cam_ros::NetworkConfig > server_
bool m_default_configured
bool waitForExistence(ros::Duration timeout=ros::Duration(-1))
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
ros::ServiceClient client_change_
void parametersCallback(l3cam_ros::NetworkConfig &config, uint32_t level)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
ROSCPP_DECL void spinOnce()
ROSCPP_DECL void shutdown()
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define ROS_BMG_UNUSED(x)
#define ROS_WARN_STREAM(args)
bool getNetworkConfiguration(l3cam_ros::GetNetworkConfiguration::Request &req, l3cam_ros::GetNetworkConfiguration::Response &res)
bool searchParam(const std::string &key, std::string &result) const
#define ROS_INFO_STREAM(args)
NodeHandle(const NodeHandle &parent, const std::string &ns)
int main(int argc, char **argv)
static std::string getErrorDescription(int error_code)
ros::ServiceClient client_get_
void setDynamicReconfigure()
l3cam_ros::GetNetworkConfiguration srv_get_
int callNetwork(l3cam_ros::NetworkConfig &config)
void loadParam(const std::string ¶m_name, T ¶m_var, const T &default_val)
int getNetworkConfiguration()
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
bool m_shutdown_requested
ros::ServiceServer srv_sensor_disconnected_
const std::string & getNamespace() const
bool sensorDisconnectedCallback(l3cam_ros::SensorDisconnected::Request &req, l3cam_ros::SensorDisconnected::Response &res)
l3cam_ros::ChangeNetworkConfiguration srv_change_
l3cam_ros
Author(s): Beamagine
autogenerated on Wed May 28 2025 02:53:15