Skip to content

Commit

Permalink
fixing trasient_local in ROS2 packages (autowarefoundation#160)
Browse files Browse the repository at this point in the history
  • Loading branch information
nik-tier4 authored Dec 11, 2020
1 parent fbbee08 commit bd48eef
Show file tree
Hide file tree
Showing 12 changed files with 12 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ NDTScanMatcher::NDTScanMatcher()
"ekf_pose_with_covariance", 100,
std::bind(&NDTScanMatcher::callbackInitialPose, this, std::placeholders::_1));
map_points_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"pointcloud_map", 1,
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
std::bind(&NDTScanMatcher::callbackMapPoints, this, std::placeholders::_1));
sensor_points_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"points_raw", 1, std::bind(&NDTScanMatcher::callbackSensorPoints, this, std::placeholders::_1));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ PoseInitializer::PoseInitializer()
"initialpose", 10,
std::bind(&PoseInitializer::callbackInitialPose, this, std::placeholders::_1));
map_points_sub_ = this->create_subscription<geometry_msgs::msg::PoseWithCovarianceStamped>(
"pointcloud_map", 1,
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
std::bind(&PoseInitializer::callbackMapPoints, this, std::placeholders::_1));

const bool use_first_gnss_topic = this->declare_parameter("use_first_gnss_topic", true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ int main(int argc, char ** argv)
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("lanelet2_map_visualizer");
auto bin_map_sub = node->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/lanelet2_map", rclcpp::QoS{1}, std::bind(&binMapCallback, std::placeholders::_1));
"input/lanelet2_map", rclcpp::QoS{1}.transient_local(), std::bind(&binMapCallback, std::placeholders::_1));

rclcpp::QoS durable_qos{1};
durable_qos.transient_local();
Expand Down
2 changes: 1 addition & 1 deletion map/map_tf_generator/nodes/map_tf_generator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class MapTFGenerator : public rclcpp::Node
viewer_frame_ = declare_parameter("viewer_frame", "viewer");

sub_ = create_subscription<sensor_msgs::msg::PointCloud2>(
"pointcloud_map", rclcpp::QoS{1},
"pointcloud_map", rclcpp::QoS{1}.transient_local(),
std::bind(&MapTFGenerator::Callback, this, std::placeholders::_1));

static_broadcaster_ = std::make_shared<tf2_ros::StaticTransformBroadcaster>(this);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -196,7 +196,7 @@ MapBasedPredictionROS::MapBasedPredictionROS()
"/perception/object_recognition/tracking/objects", 1,
std::bind(&MapBasedPredictionROS::objectsCallback, this, std::placeholders::_1));
sub_map_ = this->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"/vector_map", 10,
"/vector_map", rclcpp::QoS{10}.transient_local(),
std::bind(&MapBasedPredictionROS::mapCallback, this, std::placeholders::_1));

pub_objects_ = this->create_publisher<autoware_perception_msgs::msg::DynamicObjectArray>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ namespace traffic_light

// subscribers
map_sub_ = create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", 1, std::bind(&MapBasedDetector::mapCallback, this, _1));
"input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&MapBasedDetector::mapCallback, this, _1));
camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>(
"input/camera_info", 1, std::bind(&MapBasedDetector::cameraInfoCallback, this, _1));
route_sub_ = create_subscription<autoware_planning_msgs::msg::Route>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ MissionPlannerLanelet2::MissionPlannerLanelet2()
{
using std::placeholders::_1;
map_subscriber_ = create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", 10, std::bind(
"input/vector_map", rclcpp::QoS{10}.transient_local(), std::bind(
&MissionPlannerLanelet2::mapCallback, this,
_1));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode()
"input/vehicle_velocity", 1,
std::bind(&BehaviorVelocityPlannerNode::onVehicleVelocity, this, _1));
sub_lanelet_map_ = this->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", 10, std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1));
"input/vector_map", rclcpp::QoS(10).transient_local(), std::bind(&BehaviorVelocityPlannerNode::onLaneletMap, this, _1));
sub_traffic_light_states_ =
this->create_subscription<autoware_perception_msgs::msg::TrafficLightStateArray>(
"input/traffic_light_states", 10,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ void LaneChanger::init()
// route_handler
vector_map_subscriber_ =
create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", rclcpp::QoS{1}, std::bind(
"input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(
&RouteHandler::mapCallback, &(*route_handler_ptr_),
std::placeholders::_1));
route_subscriber_ =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ TurnSignalDecider::TurnSignalDecider(
"input/path_with_lane_id", rclcpp::QoS{1},
std::bind(&DataManager::onPathWithLaneId, &data_, _1));
map_subscription_ = this->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", rclcpp::QoS{1}, std::bind(&DataManager::onLaneletMap, &data_, _1));
"input/vector_map", rclcpp::QoS{1}.transient_local(), std::bind(&DataManager::onLaneletMap, &data_, _1));

// get ROS parameters
parameters_.lane_change_search_distance = this->declare_parameter(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ CostmapGenerator::CostmapGenerator()
sub_points_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"input/points_no_ground", 1, std::bind(&CostmapGenerator::onPoints, this, _1));
sub_lanelet_bin_map_ = this->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/vector_map", 1, std::bind(&CostmapGenerator::onLaneletMapBin, this, _1));
"input/vector_map", rclcpp::QoS(1).transient_local(), std::bind(&CostmapGenerator::onLaneletMapBin, this, _1));
sub_scenario_ = this->create_subscription<autoware_planning_msgs::msg::Scenario>(
"input/scenario", 1, std::bind(&CostmapGenerator::onScenario, this, _1));

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -318,7 +318,7 @@ ScenarioSelectorNode::ScenarioSelectorNode()
"input/parking/trajectory", rclcpp::QoS{1}, createCallback(&input_parking_.buf_trajectory));

sub_lanelet_map_ = this->create_subscription<autoware_lanelet2_msgs::msg::MapBin>(
"input/lanelet_map", rclcpp::QoS{1},
"input/lanelet_map", rclcpp::QoS{1}.transient_local(),
std::bind(&ScenarioSelectorNode::onMap, this, std::placeholders::_1));
sub_route_ = this->create_subscription<autoware_planning_msgs::msg::Route>(
"input/route", rclcpp::QoS{1},
Expand Down

0 comments on commit bd48eef

Please sign in to comment.