Classes | Macros | Functions
nm33_node.cpp File Reference
#include <ros/ros.h>
#include <rospack/rospack.h>
#include <sensor_msgs/fill_image.h>
#include <sensor_msgs/SetCameraInfo.h>
#include <image_transport/image_transport.h>
#include <camera_calibration_parsers/parse.h>
#include <opencv2/opencv.hpp>
#include <cv_bridge/cv_bridge.h>
#include <dynamic_reconfigure/server.h>
#include <opt_camera/OptNM33CameraConfig.h>
#include "opt_nm33_uvc/opt_nm33_camera.h"
Include dependency graph for nm33_node.cpp:

Go to the source code of this file.

Classes

class  OptCamNode
 

Macros

#define SET_CAMERA(methodname, paramname)
 
#define set_camera_info_method(set_camera_info_method, view_name)
 

Functions

int main (int argc, char **argv)
 

Macro Definition Documentation

#define SET_CAMERA (   methodname,
  paramname 
)
Value:
if (config_.paramname != config.paramname ) { \
camera_->methodname(config.paramname); \
}
#define set_camera_info_method (   set_camera_info_method,
  view_name 
)
Value:
bool set_camera_info_method(sensor_msgs::SetCameraInfo::Request& req, \
sensor_msgs::SetCameraInfo::Response& rsp) { \
ROS_INFO("New camera info received"); \
sensor_msgs::CameraInfo &info = req.camera_info; \
\
std::string cam_name = serial_id_+view_name; \
std::string ini_name = cam_name+".ini"; \
rospack::Rospack rp; \
try { \
std::vector<std::string> search_path; \
rp.getSearchPathFromEnv(search_path); \
rp.crawl(search_path, 1); \
std::string path; \
if(rp.find("opt_camera", path)==true) ini_name = path + "/cfg/" + ini_name; \
} catch (std::runtime_error &e) { \
} \
if (!camera_calibration_parsers::writeCalibration(ini_name, cam_name.c_str(), info)) { \
rsp.status_message = "Error writing camera_info to " + cam_name + ".ini"; \
rsp.success = false; \
} \
\
rsp.success = true; \
return true; \
}
#define set_camera_info_method(set_camera_info_method, view_name)
Definition: nm33_node.cpp:356
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)

Definition at line 356 of file nm33_node.cpp.

Function Documentation

int main ( int  argc,
char **  argv 
)

Definition at line 415 of file nm33_node.cpp.



opt_camera
Author(s): Kei Okada
autogenerated on Tue May 11 2021 02:55:43