51       ROS_WARN(
"~yaml_fliename is not specified, use default camera info parameters");
 
   58     srv_ = std::make_shared <dynamic_reconfigure::Server<Config> > (pnh);
 
   59     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   62     srv_->setCallback (f);
 
   65     if (!pnh.getParam(
"frame_id", 
frame_id_)) {
 
   66       ROS_WARN(
"~frame_id is not specified, use camera as frame_id");
 
   70       ROS_WARN(
"~parent_frame_id is not specified, use base_link as parent_frame_id");
 
   81     if (!pnh.getParam(
"sync_pointcloud", sync_pointcloud)) {
 
   82       sync_pointcloud = 
false;
 
   84     if (sync_pointcloud) {
 
   85       ROS_INFO(
"~sync_pointcloud is specified, synchronize ~camera_info to pointcloud");
 
   90       if (!pnh.getParam(
"sync_image", sync_image)) {
 
   94         ROS_INFO(
"~sync_image is specified, synchronize ~camera_info to image");
 
   99         ROS_INFO(
"~sync_image or ~sync_pointcloud are not specified, use static_rate");
 
  101         pnh.param(
"static_rate", static_rate, 30.0); 
 
  117     visualization_msgs::InteractiveMarker int_marker;
 
  119     int_marker.name = 
"camera info";
 
  127     const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 
  130     geometry_msgs::PoseStamped new_pose, transformed_pose;
 
  131     new_pose.pose = feedback->pose;
 
  132     new_pose.header = feedback->header;
 
  136         new_pose, transformed_pose);
 
  157     sensor_msgs::CameraInfo camera_info;
 
  163       camera_info.distortion_model =
 
  165       std::vector<double> 
D, 
K, 
R, 
P;
 
  166       boost::array<double, 9ul> Kl, Rl;
 
  167       boost::array<double, 12ul> Pl;
 
  170       std::memcpy(&Kl[0], &
K[0], 
sizeof(
double)*9);
 
  172       std::memcpy(&Rl[0], &
R[0], 
sizeof(
double)*9);
 
  174       std::memcpy(&Pl[0], &
P[0], 
sizeof(
double)*12);
 
  182       camera_info.width = 
width_;
 
  184       camera_info.D.resize(5, 0);
 
  185       camera_info.K.assign(0.0);
 
  186       camera_info.R.assign(0.0);
 
  187       camera_info.P.assign(0.0);
 
  188       camera_info.K[0] = camera_info.K[4] = 
f_;
 
  190       camera_info.K[0] = camera_info.P[0] = camera_info.K[4] = camera_info.P[5] = 
f_;
 
  191       camera_info.K[2] = camera_info.P[2] = 
width_ / 2.0;
 
  192       camera_info.K[5] = camera_info.P[6] = 
height_ / 2.0;
 
  193       camera_info.K[8] = camera_info.P[10] = 1.0;
 
  194       camera_info.R[0] = camera_info.R[4] = camera_info.R[8] = 1.0;
 
  212     const sensor_msgs::PointCloud2::ConstPtr& msg)
 
  218     const sensor_msgs::Image::ConstPtr& msg)
 
  232 int main(
int argc, 
char** argv)