Skip to content

Commit

Permalink
Fixed compilation of all components on ros2 foxy
Browse files Browse the repository at this point in the history
  • Loading branch information
mdrwiega committed Jul 22, 2021
1 parent f47d6e9 commit c489b8f
Show file tree
Hide file tree
Showing 6 changed files with 12 additions and 4 deletions.
4 changes: 3 additions & 1 deletion cliff_detector/include/cliff_detector/cliff_detector_node.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/msg/image.hpp>
#include <geometry_msgs/msg/polygon_stamped.hpp>
#include <rcl_interfaces/msg/set_parameters_result.hpp>
Expand Down Expand Up @@ -39,6 +39,8 @@ class CliffDetectorNode : public rclcpp::Node {
rclcpp::Publisher<geometry_msgs::msg::PolygonStamped>::SharedPtr pub_points_;
/// Contains cliff detection method implementation
cliff_detector::CliffDetector detector_;

OnSetParametersCallbackHandle::SharedPtr params_callback_handle_;
};

} // namespace cliff_detector
2 changes: 1 addition & 1 deletion cliff_detector/src/cliff_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ namespace cliff_detector {
CliffDetectorNode::CliffDetectorNode()
: Node("cliff_detector")
{
set_on_parameters_set_callback(
params_callback_handle_ = add_on_set_parameters_callback(
std::bind(&CliffDetectorNode::parametersCallback, this, std::placeholders::_1));

// Declare all node parameters
Expand Down
2 changes: 2 additions & 0 deletions depth_sensor_pose/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ find_package(image_transport REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(pcl_conversions REQUIRED)
find_package(cv_bridge REQUIRED)

find_package(PCL REQUIRED)
find_package(Eigen3 REQUIRED)
Expand All @@ -25,6 +26,7 @@ add_library(DepthSensorPoseNode
src/depth_sensor_pose.cpp
src/depth_sensor_pose_node.cpp
)

ament_target_dependencies(DepthSensorPoseNode
rclcpp
std_msgs
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#pragma once

#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.h>
#include <image_transport/image_transport.hpp>
#include <std_msgs/msg/float64.h>
#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/laser_scan.hpp>
Expand Down Expand Up @@ -51,6 +51,8 @@ class DepthSensorPoseNode : public rclcpp::Node {
image_transport::Publisher pub_;

depth_sensor_pose::DepthSensorPose estimator_;

OnSetParametersCallbackHandle::SharedPtr params_callback_handle_;
};

} // namespace depth_sensor_pose
2 changes: 1 addition & 1 deletion depth_sensor_pose/src/depth_sensor_pose_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ namespace depth_sensor_pose {
DepthSensorPoseNode::DepthSensorPoseNode()
: Node("depth_sensor_pose")
{
set_on_parameters_set_callback(
params_callback_handle_ = add_on_set_parameters_callback(
std::bind(&DepthSensorPoseNode::parametersCallback, this, std::placeholders::_1));

declare_parameter("output_frame_id", "camera_depth_frame");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ class NavLayerFromPoints : public nav2_costmap_2d::CostmapLayer {

void onInitialize() override;

void reset() override {}

void updateBounds(double origin_x, double origin_y, double origin_z,
double* min_x, double* min_y, double* max_x, double* max_y) override;

Expand Down

0 comments on commit c489b8f

Please sign in to comment.