17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H 24 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" 25 #include "cartographer_ros_msgs/TrajectoryOptions.h" 30 ::cartographer::mapping::proto::TrajectoryBuilderOptions
51 ::cartographer::mapping::proto::InitialTrajectoryPose
63 bool FromRosMessage(
const cartographer_ros_msgs::TrajectoryOptions& msg,
72 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_TRAJECTORY_OPTIONS_H double imu_sampling_ratio
double odometry_sampling_ratio
std::string tracking_frame
bool publish_frame_projected_to_2d
double fixed_frame_pose_sampling_ratio
int num_subdivisions_per_laser_scan
double landmarks_sampling_ratio
::cartographer::mapping::proto::TrajectoryBuilderOptions trajectory_builder_options
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::string published_frame
cartographer_ros_msgs::TrajectoryOptions ToRosMessage(const TrajectoryOptions &options)
::cartographer::mapping::proto::InitialTrajectoryPose CreateInitialTrajectoryPose(::cartographer::common::LuaParameterDictionary *lua_parameter_dictionary)