17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_H 23 #include <unordered_map> 24 #include <unordered_set> 35 #include "cartographer_ros_msgs/FinishTrajectory.h" 36 #include "cartographer_ros_msgs/SensorTopics.h" 37 #include "cartographer_ros_msgs/StartTrajectory.h" 38 #include "cartographer_ros_msgs/StatusResponse.h" 39 #include "cartographer_ros_msgs/SubmapEntry.h" 40 #include "cartographer_ros_msgs/SubmapList.h" 41 #include "cartographer_ros_msgs/SubmapQuery.h" 42 #include "cartographer_ros_msgs/TrajectoryOptions.h" 43 #include "cartographer_ros_msgs/WriteState.h" 44 #include "nav_msgs/Odometry.h" 46 #include "sensor_msgs/Imu.h" 47 #include "sensor_msgs/LaserScan.h" 48 #include "sensor_msgs/MultiEchoLaserScan.h" 49 #include "sensor_msgs/NavSatFix.h" 50 #include "sensor_msgs/PointCloud2.h" 59 std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
82 std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId>>
84 const std::vector<TrajectoryOptions>& bags_options)
const;
95 const nav_msgs::Odometry::ConstPtr& msg);
97 const sensor_msgs::NavSatFix::ConstPtr& msg);
99 int trajectory_id,
const std::string& sensor_id,
100 const cartographer_ros_msgs::LandmarkList::ConstPtr& msg);
102 const sensor_msgs::Imu::ConstPtr& msg);
104 const sensor_msgs::LaserScan::ConstPtr& msg);
106 int trajectory_id,
const std::string& sensor_id,
107 const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
109 const sensor_msgs::PointCloud2::ConstPtr& msg);
115 void LoadState(
const std::string& state_filename,
bool load_frozen_state);
131 cartographer_ros_msgs::SubmapQuery::Request& request,
132 cartographer_ros_msgs::SubmapQuery::Response& response);
134 cartographer_ros_msgs::StartTrajectory::Request& request,
135 cartographer_ros_msgs::StartTrajectory::Response& response);
137 cartographer_ros_msgs::FinishTrajectory::Request& request,
138 cartographer_ros_msgs::FinishTrajectory::Response& response);
140 cartographer_ros_msgs::WriteState::Response& response);
143 std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId>
146 const cartographer_ros_msgs::SensorTopics& topics)
const;
148 const cartographer_ros_msgs::SensorTopics& topics);
150 const cartographer_ros_msgs::SensorTopics& topics,
184 const double odometry_sampling_ratio,
185 const double fixed_frame_pose_sampling_ratio,
186 const double imu_sampling_ratio,
187 const double landmark_sampling_ratio)
188 : rangefinder_sampler(rangefinder_sampling_ratio),
189 odometry_sampler(odometry_sampling_ratio),
190 fixed_frame_pose_sampler(fixed_frame_pose_sampling_ratio),
191 imu_sampler(imu_sampling_ratio),
192 landmark_sampler(landmark_sampling_ratio) {}
206 std::unordered_map<int, bool> is_active_trajectory_
GUARDED_BY(mutex_);
215 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_H bool FinishTrajectory(int trajectory_id)
::ros::Publisher trajectory_node_list_publisher_
Node & operator=(const Node &)=delete
void SerializeState(const std::string &filename)
::cartographer::common::FixedRatioSampler landmark_sampler
std::vector<::ros::ServiceServer > service_servers_
void FinishAllTrajectories()
std::vector< std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId > > ComputeDefaultSensorIdsForMultipleBags(const std::vector< TrajectoryOptions > &bags_options) const
::ros::Publisher landmark_poses_list_publisher_
void HandleMultiEchoLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::MultiEchoLaserScan::ConstPtr &msg)
::cartographer::common::FixedRatioSampler fixed_frame_pose_sampler
bool ValidateTrajectoryOptions(const TrajectoryOptions &options)
std::unordered_map< int, TrajectorySensorSamplers > sensor_samplers_
void PublishSubmapList(const ::ros::WallTimerEvent &timer_event)
int AddOfflineTrajectory(const std::set< cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &options)
Node(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
cartographer::common::Mutex mutex_
const NodeOptions node_options_
tf2_ros::TransformBroadcaster tf_broadcaster_
void AddExtrapolator(int trajectory_id, const TrajectoryOptions &options)
bool HandleStartTrajectory(cartographer_ros_msgs::StartTrajectory::Request &request, cartographer_ros_msgs::StartTrajectory::Response &response)
::ros::Publisher scan_matched_point_cloud_publisher_
void PublishTrajectoryNodeList(const ::ros::WallTimerEvent &timer_event)
void RunFinalOptimization()
TrajectorySensorSamplers(const double rangefinder_sampling_ratio, const double odometry_sampling_ratio, const double fixed_frame_pose_sampling_ratio, const double imu_sampling_ratio, const double landmark_sampling_ratio)
void SpinOccupancyGridThreadForever()
::ros::Publisher submap_list_publisher_
void HandlePointCloud2Message(int trajectory_id, const std::string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg)
cartographer_ros_msgs::StatusResponse FinishTrajectoryUnderLock(int trajectory_id) REQUIRES(mutex_)
void HandleOdometryMessage(int trajectory_id, const std::string &sensor_id, const nav_msgs::Odometry::ConstPtr &msg)
void HandleImuMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg)
void HandleLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg)
::ros::Publisher constraint_list_publisher_
::ros::NodeHandle node_handle_
std::vector<::ros::WallTimer > wall_timers_
int AddTrajectory(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics)
MapBuilderBridge map_builder_bridge_ GUARDED_BY(mutex_)
void HandleNavSatFixMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::NavSatFix::ConstPtr &msg)
void PublishConstraintList(const ::ros::WallTimerEvent &timer_event)
void LoadState(const std::string &state_filename, bool load_frozen_state)
std::unordered_set< std::string > subscribed_topics_
void AddSensorSamplers(int trajectory_id, const TrajectoryOptions &options)
::ros::NodeHandle * node_handle()
::cartographer::common::FixedRatioSampler imu_sampler
bool HandleFinishTrajectory(cartographer_ros_msgs::FinishTrajectory::Request &request, cartographer_ros_msgs::FinishTrajectory::Response &response)
void StartTrajectoryWithDefaultTopics(const TrajectoryOptions &options)
::cartographer::common::FixedRatioSampler odometry_sampler
std::unordered_map< int, std::vector< Subscriber > > subscribers_
bool HandleWriteState(cartographer_ros_msgs::WriteState::Request &request, cartographer_ros_msgs::WriteState::Response &response)
std::map< int, ::cartographer::mapping::PoseExtrapolator > extrapolators_
void HandleLandmarkMessage(int trajectory_id, const std::string &sensor_id, const cartographer_ros_msgs::LandmarkList::ConstPtr &msg)
::ros::Subscriber subscriber
bool HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
void LaunchSubscribers(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics, int trajectory_id)
bool ValidateTopicNames(const ::cartographer_ros_msgs::SensorTopics &topics, const TrajectoryOptions &options)
::cartographer::common::FixedRatioSampler rangefinder_sampler
tf2_ros::Buffer * tf_buffer
void PublishTrajectoryStates(const ::ros::WallTimerEvent &timer_event)
void PublishLandmarkPosesList(const ::ros::WallTimerEvent &timer_event)
std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId > ComputeExpectedSensorIds(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics) const