Skip to content

Commit

Permalink
Passing fixed_frame and target_frame to Convert object. (ros-drivers#330
Browse files Browse the repository at this point in the history
)
  • Loading branch information
Joshua Whitley authored and wep21 committed Dec 27, 2021
1 parent 3dda34a commit efc1dcd
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@ velodyne_convert_node:
ros__parameters:
calibration: VLP16db.yaml
model: VLP16
target_frame: velodyne
fixed_frame: velodyne
min_range: 0.9
max_range: 130.0
view_direction: 0.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@ velodyne_convert_node:
ros__parameters:
calibration: VeloView-VLP-32C.yaml
model: 32C
target_frame: velodyne
fixed_frame: velodyne
min_range: 0.9
max_range: 200.0
view_direction: 0.0
Expand Down
6 changes: 3 additions & 3 deletions velodyne_pointcloud/src/conversions/convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,10 +100,10 @@ Convert::Convert(const rclcpp::NodeOptions & options)
view_width_desc.floating_point_range.push_back(view_width_range);
double view_width = this->declare_parameter("view_width", 2.0 * M_PI, view_width_desc);

bool organize_cloud = this->declare_parameter("organize_cloud", true);
bool organize_cloud = this->declare_parameter("organize_cloud", false);

std::string target_frame = this->declare_parameter("target_frame", "");
std::string fixed_frame = this->declare_parameter("fixed_frame", "");
std::string target_frame = this->declare_parameter("target_frame", "velodyne");
std::string fixed_frame = this->declare_parameter("fixed_frame", "velodyne");

RCLCPP_INFO(this->get_logger(), "correction angles: %s", calibration_file.c_str());

Expand Down

0 comments on commit efc1dcd

Please sign in to comment.