26 base_link(
"base_link")
43 for (
int i = 0; i < names.
size(); ++i)
45 free_params.push_back(
static_cast<std::string
>(names[i]));
54 nh.
getParam(
"free_frames", free_frame_params);
57 for (
int i = 0; i < free_frame_params.
size(); ++i)
60 params.
name =
static_cast<std::string
>(free_frame_params[i][
"name"]);
61 params.
x =
static_cast<bool>(free_frame_params[i][
"x"]);
62 params.
y =
static_cast<bool>(free_frame_params[i][
"y"]);
63 params.
z =
static_cast<bool>(free_frame_params[i][
"z"]);
64 params.
roll =
static_cast<bool>(free_frame_params[i][
"roll"]);
65 params.
pitch =
static_cast<bool>(free_frame_params[i][
"pitch"]);
66 params.
yaw =
static_cast<bool>(free_frame_params[i][
"yaw"]);
71 if (nh.
hasParam(
"free_frames_initial_values"))
76 nh.
getParam(
"free_frames_initial_values", initial_value_params);
79 for (
int i = 0; i < initial_value_params.
size(); ++i)
82 params.
name =
static_cast<std::string
>(initial_value_params[i][
"name"]);
83 params.
x =
static_cast<double>(initial_value_params[i][
"x"]);
84 params.
y =
static_cast<double>(initial_value_params[i][
"y"]);
85 params.
z =
static_cast<double>(initial_value_params[i][
"z"]);
86 params.
roll =
static_cast<double>(initial_value_params[i][
"roll"]);
87 params.
pitch =
static_cast<double>(initial_value_params[i][
"pitch"]);
88 params.
yaw =
static_cast<double>(initial_value_params[i][
"yaw"]);
101 for (
int i = 0; i < model_params.
size(); ++i)
104 params.
name =
static_cast<std::string
>(model_params[i][
"name"]);
105 params.
type =
static_cast<std::string
>(model_params[i][
"type"]);
106 params.
params = model_params[i];
116 nh.
getParam(
"error_blocks", error_params);
119 for (
int i = 0; i < error_params.
size(); ++i)
122 params.
name =
static_cast<std::string
>(error_params[i][
"name"]);
123 params.
type =
static_cast<std::string
>(error_params[i][
"type"]);
124 params.
params = error_params[i];