26 base_link(
"base_link")
42 for (
int i = 0; i < names.
size(); ++i)
44 free_params.push_back(static_cast<std::string>(names[i]));
53 nh.
getParam(
"free_frames", free_frame_params);
56 for (
int i = 0; i < free_frame_params.
size(); ++i)
59 params.
name =
static_cast<std::string
>(free_frame_params[i][
"name"]);
60 params.
x =
static_cast<bool>(free_frame_params[i][
"x"]);
61 params.
y =
static_cast<bool>(free_frame_params[i][
"y"]);
62 params.
z =
static_cast<bool>(free_frame_params[i][
"z"]);
63 params.
roll =
static_cast<bool>(free_frame_params[i][
"roll"]);
64 params.
pitch =
static_cast<bool>(free_frame_params[i][
"pitch"]);
65 params.
yaw =
static_cast<bool>(free_frame_params[i][
"yaw"]);
70 if (nh.
hasParam(
"free_frames_initial_values"))
75 nh.
getParam(
"free_frames_initial_values", initial_value_params);
78 for (
int i = 0; i < initial_value_params.
size(); ++i)
81 params.
name =
static_cast<std::string
>(initial_value_params[i][
"name"]);
82 params.
x =
static_cast<double>(initial_value_params[i][
"x"]);
83 params.
y =
static_cast<double>(initial_value_params[i][
"y"]);
84 params.
z =
static_cast<double>(initial_value_params[i][
"z"]);
85 params.
roll =
static_cast<double>(initial_value_params[i][
"roll"]);
86 params.
pitch =
static_cast<double>(initial_value_params[i][
"pitch"]);
87 params.
yaw =
static_cast<double>(initial_value_params[i][
"yaw"]);
100 for (
int i = 0; i < model_params.
size(); ++i)
103 params.
name =
static_cast<std::string
>(model_params[i][
"name"]);
104 params.
type =
static_cast<std::string
>(model_params[i][
"type"]);
105 params.
params = model_params[i];
115 nh.
getParam(
"error_blocks", error_params);
118 for (
int i = 0; i < error_params.
size(); ++i)
121 params.
name =
static_cast<std::string
>(error_params[i][
"name"]);
122 params.
type =
static_cast<std::string
>(error_params[i][
"type"]);
123 params.
params = error_params[i];
std::vector< FreeFrameInitialValue > free_frames_initial_values
Type const & getType() const
std::vector< std::string > free_params
bool LoadFromROS(ros::NodeHandle &nh)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Calibration code lives under this namespace.
XmlRpc::XmlRpcValue params
std::vector< FreeFrameParams > free_frames
std::vector< Params > models
std::vector< Params > error_blocks
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const