23 #include "glog/logging.h" 29 void CheckTrajectoryOptions(
const TrajectoryOptions& options) {
30 CHECK_GE(options.num_subdivisions_per_laser_scan, 1);
31 CHECK_GE(options.num_laser_scans + options.num_multi_echo_laser_scans +
32 options.num_point_clouds,
34 <<
"Configuration error: 'num_laser_scans', " 35 "'num_multi_echo_laser_scans' and 'num_point_clouds' are " 36 "all zero, but at least one is required.";
43 lua_parameter_dictionary) {
46 ::cartographer::mapping::CreateTrajectoryBuilderOptions(
47 lua_parameter_dictionary->
GetDictionary(
"trajectory_builder").get());
49 lua_parameter_dictionary->
GetString(
"tracking_frame");
51 lua_parameter_dictionary->
GetString(
"published_frame");
54 lua_parameter_dictionary->
GetBool(
"provide_odom_frame");
59 lua_parameter_dictionary->
GetBool(
"publish_frame_projected_to_2d");
66 "num_subdivisions_per_laser_scan");
70 lua_parameter_dictionary->
GetDouble(
"rangefinder_sampling_ratio");
72 lua_parameter_dictionary->
GetDouble(
"odometry_sampling_ratio");
74 lua_parameter_dictionary->
GetDouble(
"fixed_frame_pose_sampling_ratio");
76 lua_parameter_dictionary->
GetDouble(
"imu_sampling_ratio");
78 lua_parameter_dictionary->
GetDouble(
"landmarks_sampling_ratio");
79 CheckTrajectoryOptions(options);
92 ::cartographer::mapping::proto::InitialTrajectoryPose
95 ::cartographer::mapping::proto::InitialTrajectoryPose
pose;
96 pose.set_to_trajectory_id(
98 *pose.mutable_relative_pose() =
100 lua_parameter_dictionary->
GetDictionary(
"relative_pose").get()));
102 lua_parameter_dictionary->
HasKey(
"timestamp")
121 msg.num_subdivisions_per_laser_scan;
126 msg.fixed_frame_pose_sampling_ratio;
130 msg.trajectory_builder_options_proto)) {
131 LOG(ERROR) <<
"Failed to parse protobuf";
134 CheckTrajectoryOptions(*options);
140 cartographer_ros_msgs::TrajectoryOptions msg;
159 &msg.trajectory_builder_options_proto);
double imu_sampling_ratio
std::string GetString(const std::string &key)
double odometry_sampling_ratio
std::string tracking_frame
int GetNonNegativeInt(const std::string &key)
double GetDouble(const std::string &key)
bool publish_frame_projected_to_2d
double fixed_frame_pose_sampling_ratio
int num_subdivisions_per_laser_scan
double landmarks_sampling_ratio
int64 ToUniversal(const Time time)
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
::cartographer::common::Time FromRos(const ::ros::Time &time)
TrajectoryOptions CreateTrajectoryOptions(::cartographer::common::LuaParameterDictionary *const lua_parameter_dictionary)
int num_multi_echo_laser_scans
bool FromRosMessage(const cartographer_ros_msgs::TrajectoryOptions &msg, TrajectoryOptions *options)
double rangefinder_sampling_ratio
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
std::string published_frame
cartographer_ros_msgs::TrajectoryOptions ToRosMessage(const TrajectoryOptions &options)
::cartographer::mapping::proto::InitialTrajectoryPose CreateInitialTrajectoryPose(::cartographer::common::LuaParameterDictionary *lua_parameter_dictionary)
bool GetBool(const std::string &key)
bool HasKey(const std::string &key) const