Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 11 additions & 2 deletions ethzasl_icp_mapper/include/ethzasl_icp_mapper/dynamic_mapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,8 @@ class Mapper {
void waitForMapBuildingCompleted();
void updateIcpMap(const DP *new_map_point_cloud);
void loadExternalParameters();
void publishTransforms(const ros::Time &stamp);
void publishCallback(const ros::TimerEvent& event);

// Services
bool getPointMap(map_msgs::GetPointMap::Request &req,
Expand Down Expand Up @@ -102,8 +104,10 @@ class Mapper {
ros::Publisher scan_pub_;
ros::Publisher outlier_pub_;
ros::Publisher odom_pub_;
ros::Publisher odom_base_pub_;
ros::Publisher odom_error_pub_;
ros::Publisher pose_pub_;
ros::Publisher pose_base_pub_;

// Services
ros::ServiceServer get_point_map_srv_;
Expand All @@ -118,6 +122,9 @@ class Mapper {
ros::ServiceServer initial_transform_srv_;
ros::ServiceServer load_published_map_srv_;

// Timers
ros::Timer publish_timer_;

// Time
ros::Time map_creation_time_;
ros::Time last_poin_cloud_time_;
Expand All @@ -131,6 +138,7 @@ class Mapper {
PM::ICPSequence icp_;
shared_ptr<PM::Transformation> transformation_;
shared_ptr<PM::DataPointsFilter> radius_filter_;
int dimp1_;

// multi-threading mapper
#if BOOST_VERSION >= 104100
Expand All @@ -144,14 +152,15 @@ class Mapper {

MapperParameters parameters_;
int odom_received_;
PM::TransformationParameters T_local_map_to_map_;
PM::TransformationParameters T_scanner_to_map_;
PM::TransformationParameters T_scanner_to_odom_;
PM::TransformationParameters T_odom_to_map_;
boost::thread publish_thread_;
boost::mutex publish_lock_;
boost::mutex icp_map_lock_;
int scan_counter_;

tf::TransformListener tf_listener_;
tf::TransformBroadcaster tf_broadcaster_;
};

}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ struct MapperParameters {
bool subscribe_cloud;
bool subscribe_map;
std::string sensor_frame;
std::string base_frame;
std::string odom_frame;
std::string map_frame;
std::string tf_map_frame;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,8 @@ Parameters for Center for robotics summer school 2019

<launch>

<arg name="map_frame" default="/map"/>

<node name="mapper" type="dynamic_mapper_node" pkg="ethzasl_icp_mapper" output="screen" >
<remap from="cloud_in" to="/rslidar_points" />
<param name="subscribe_scan" value="false"/>
Expand All @@ -16,11 +18,10 @@ Parameters for Center for robotics summer school 2019

<!--Put that back! -->
<param name="publishMapTf" value="false"/>
<param name="odom_frame" value="/world" /> #lidar

<param name="lidar_frame" value="rslidar" />
<param name="map_frame" value="/icp_map" />
<param name="tf_map_frame" value="/map" />
<param name="odom_frame" value="/realsense_t265_odom_frame" />
<param name="base_frame" value="/base" />
<param name="lidar_frame" value="/rslidar" />
<param name="map_frame" value="$(arg map_frame)" />
<param name="useROSLogger" value="true" />
<param name="inputQueueSize" value="1" />
<param name="tfRefreshPeriod" value="0.005" />
Expand All @@ -29,7 +30,9 @@ Parameters for Center for robotics summer school 2019
<param name="minReadingPointCount" value="1000" />
<param name="minMapPointCount" value="10000" /> <!-- quick fix to have map published each time -->
<param name="skip_frames" value="2" /> <!-- Skip this many frames before processing a new one-->

<param name="publish_rate" value="100" />
</node>

<node pkg="tf" type="static_transform_publisher" name="tracking_cam_to_base"
args="-0.309 -0.008 -0.351 0 0 0 1 /realsense_t265_pose_frame /base 100"/>
</launch>
Loading