写在前面
launch一个文件时,roslaunch首先检查roscore是否已经启动,如果没有则启动roscore。
roscore会做三件事:
- 启动master节点,该节点是隐藏的,用于通过消息名查询目标节点,实现消息、服务在各个节点之间的连接
- 启动parameter server,用于设置与查询参数
- 启动日志节点,记录所有消息收发和stdout、stderr,
rosparam 设置与访问方式
parameter server参数服务器,可以方便地通过设置参数来改变节点的行为。参数服务器内的参数是以key,value的形式交互。 其中key可以加前缀作为命名空间构成多级参数。 进行rosparam 设置与访问方式主要有如下三种方式:
- ros调试命令 rosparam set / rosparam get
- launch param /rosparam元素
- C++/Python API
– roscpp: ros::param::set / ros::param::get
–rospy: set_param / get_param
通常方法2和方法3是联系在一起的,通过2定义程序中经常需要调整的量,然后在程序中使用3进行获取。下面着重讲一下方法2与3
- 简单(少量)参数设置与调用
仅仅使用param 设置几个参数,并包含其默认值 - 复杂(大量)参数设置与调用
先通过一个param加载yaml文件,然后通过yaml文件来加载大量参数
使用示例
- launch文件 设置参数
其中vins_folder 是简单参数设置,config_file是复杂参数设置
<launch>
<arg name="config_path" default = "$(find feature_tracker)/../config/euroc/euroc_config.yaml" />
<arg name="vins_path" default = "$(find feature_tracker)/../config/../" />
<node name="vins_mono_feature_tracker" pkg="feature_tracker" type="feature_tracker" output="screen" >
<param name="config_file" type="string" value="$(arg config_path)" />
<param name="vins_folder" type="string" value="$(arg vins_path)" />
</node>
</launch>
- C++ API
– getParam 获取单个参数
– 通过getParam获取yaml文件名后,再通过fsSettings 读取yaml内容
#include <ros/ros.h>
#include <opencv2/highgui/highgui.hpp>
std::string IMAGE_TOPIC;
std::string IMU_TOPIC;
std::vector<std::string> CAM_NAMES;
std::string FISHEYE_MASK;
int MAX_CNT;
int MIN_DIST;
int WINDOW_SIZE;
int FREQ;
double F_THRESHOLD;
int SHOW_TRACK;
int STEREO_TRACK;
int EQUALIZE;
int ROW;
int COL;
int FOCAL_LENGTH;
int FISHEYE;
bool PUB_THIS_FRAME;
template <typename T>
T readParam(ros::NodeHandle &n, std::string name)
{
T ans;
if (n.getParam(name, ans))
{
ROS_INFO_STREAM("Loaded " << name << ": " << ans);
}
else
{
ROS_ERROR_STREAM("Failed to load " << name);
n.shutdown();
}
return ans;
}
void readParameters(ros::NodeHandle &n)
{
std::string config_file;
config_file = readParam<std::string>(n, "config_file");
cv::FileStorage fsSettings(config_file, cv::FileStorage::READ);
if(!fsSettings.isOpened())
{
std::cerr << "ERROR: Wrong path to settings" << std::endl;
}
std::string VINS_FOLDER_PATH = readParam<std::string>(n, "vins_folder"); //读取单个参数
//读取yaml
fsSettings["image_topic"] >> IMAGE_TOPIC;
fsSettings["imu_topic"] >> IMU_TOPIC;
MAX_CNT = fsSettings["max_cnt"];
MIN_DIST = fsSettings["min_dist"];
ROW = fsSettings["image_height"];
COL = fsSettings["image_width"];
FREQ = fsSettings["freq"];
F_THRESHOLD = fsSettings["F_threshold"];
SHOW_TRACK = fsSettings["show_track"];
EQUALIZE = fsSettings["equalize"];
FISHEYE = fsSettings["fisheye"];
if (FISHEYE == 1)
FISHEYE_MASK = VINS_FOLDER_PATH + "config/fisheye_mask.jpg";
CAM_NAMES.push_back(config_file);
WINDOW_SIZE = 20;
STEREO_TRACK = false;
FOCAL_LENGTH = 460;
PUB_THIS_FRAME = false;
if (FREQ == 0)
FREQ = 100;
fsSettings.release();
}
- yaml文件如下
%YAML:1.0
#common parameters
imu_topic: "/imu0"
image_topic: "/cam0/image_raw"
output_path: "/home/hualong/Documents/vins_output"
#camera calibration
model_type: PINHOLE
camera_name: camera
image_width: 752
image_height: 480
distortion_parameters:
k1: -2.917e-01
k2: 8.228e-02
p1: 5.333e-05
p2: -1.578e-04
projection_parameters:
fx: 4.616e+02
fy: 4.603e+02
cx: 3.630e+02
cy: 2.481e+02
# Extrinsic parameter between IMU and Camera.
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
# 2 Don't know anything about extrinsic parameters. You don't need to give R,T. We will try to calibrate it. Do some rotation movement at beginning.
#If you choose 0 or 1, you should write down the following matrix.
#Rotation from camera frame to imu frame, imu^R_cam
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.0148655429818, -0.999880929698, 0.00414029679422,
0.999557249008, 0.0149672133247, 0.025715529948,
-0.0257744366974, 0.00375618835797, 0.999660727178]
#Translation from camera frame to imu frame, imu^T_cam
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [-0.0216401454975,-0.064676986768, 0.00981073058949]
#feature traker paprameters
max_cnt: 150 # max feature number in feature tracking
min_dist: 30 # min distance between two features
freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
F_threshold: 1.0 # ransac threshold (pixel)
show_track: 1 # publish tracking image as topic
equalize: 1 # if image is too dark or light, trun on equalize to find enough features
fisheye: 0 # if using fisheye, trun on it. A circle mask will be loaded to remove edge noisy points
#optimization parameters
max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time
max_num_iterations: 8 # max solver itrations, to guarantee real time
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
#imu parameters The more accurate parameters you provide, the better performance
acc_n: 0.08 # accelerometer measurement noise standard deviation. #0.2 0.04
gyr_n: 0.004 # gyroscope measurement noise standard deviation. #0.05 0.004
acc_w: 0.00004 # accelerometer bias random work noise standard deviation. #0.02
gyr_w: 2.0e-6 # gyroscope bias random work noise standard deviation. #4.0e-5
g_norm: 9.81007 # gravity magnitude
#loop closure parameters
loop_closure: 1 # start loop closure
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
fast_relocalization: 0 # useful in real-time and large project
pose_graph_save_path: "/home/tony-ws1/output/pose_graph/" # save and load path
#unsynchronization parameters
estimate_td: 0 # online estimate time offset between camera and imu
td: 0.0 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
#rolling shutter parameters
rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera
rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).
#visualization parameters
save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0
visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results
visualize_camera_size: 0.4 # size of camera marker in RVIZ