Skip to content

Commit

Permalink
use "std_msgs/msg/bool"
Browse files Browse the repository at this point in the history
  • Loading branch information
tpoignonec committed Jan 8, 2024
1 parent 5bf88e3 commit b8fce47
Show file tree
Hide file tree
Showing 4 changed files with 9 additions and 6 deletions.
2 changes: 2 additions & 0 deletions fd_controllers/ee_pose_broadcaster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ find_package(rclcpp_lifecycle REQUIRED)
find_package(rcutils REQUIRED)
find_package(realtime_tools REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(example_interfaces REQUIRED)
find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3)
Expand All @@ -34,6 +35,7 @@ ament_target_dependencies(ee_pose_broadcaster
rcutils
realtime_tools
geometry_msgs
std_msgs
eigen3_cmake_module
Eigen3
example_interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "realtime_tools/realtime_publisher.h"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "example_interfaces/msg/bool.hpp"
#include "std_msgs/msg/bool.hpp"

namespace ee_pose_broadcaster
{
Expand Down Expand Up @@ -77,8 +77,8 @@ class EePoseBroadcaster : public controller_interface::ControllerInterface
std::shared_ptr<realtime_tools::RealtimePublisher<geometry_msgs::msg::PoseStamped>>
realtime_ee_pose_publisher_;

std::shared_ptr<rclcpp::Publisher<example_interfaces::msg::Bool>> fd_button_publisher_;
std::shared_ptr<realtime_tools::RealtimePublisher<example_interfaces::msg::Bool>>
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Bool>> fd_button_publisher_;
std::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>
realtime_fd_button_publisher_;
};

Expand Down
3 changes: 2 additions & 1 deletion fd_controllers/ee_pose_broadcaster/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,9 @@
<depend>controller_interface</depend>
<depend>hardware_interface</depend>
<depend>rclcpp_lifecycle</depend>
<depend>geometry_msgs</depend>
<depend>realtime_tools</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>

<test_depend>ament_cmake_gmock</test_depend>
<test_depend>controller_manager</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,11 +157,11 @@ EePoseBroadcaster::on_configure(const rclcpp_lifecycle::State & /*previous_state
std::make_shared<realtime_tools::RealtimePublisher<geometry_msgs::msg::PoseStamped>>(
ee_pose_publisher_);

fd_button_publisher_ = get_node()->create_publisher<example_interfaces::msg::Bool>(
fd_button_publisher_ = get_node()->create_publisher<std_msgs::msg::Bool>(
"button_state", rclcpp::SystemDefaultsQoS());

realtime_fd_button_publisher_ =
std::make_shared<realtime_tools::RealtimePublisher<example_interfaces::msg::Bool>>(
std::make_shared<realtime_tools::RealtimePublisher<std_msgs::msg::Bool>>(
fd_button_publisher_);
} catch (const std::exception & e) {
// get_node() may throw, logging raw here
Expand Down

0 comments on commit b8fce47

Please sign in to comment.