Skip to content

Commit

Permalink
Update the Puma messages to use the new clearpath_motor_msgs package
Browse files Browse the repository at this point in the history
  • Loading branch information
civerachb-cpr committed Sep 30, 2024
1 parent 9c31702 commit d32075b
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 13 deletions.
4 changes: 2 additions & 2 deletions clearpath_platform/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ find_package(controller_manager_msgs REQUIRED)
find_package(clearpath_platform_msgs REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(puma_motor_msgs REQUIRED)
find_package(clearpath_motor_msgs REQUIRED)
find_package(rclcpp REQUIRED)

find_package(geometry_msgs REQUIRED)
Expand Down Expand Up @@ -162,7 +162,7 @@ target_include_directories(

ament_target_dependencies(
puma_hardware
puma_motor_msgs
clearpath_motor_msgs
clearpath_platform_msgs
hardware_interface
pluginlib
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/joint_state.hpp"

#include "puma_motor_msgs/msg/feedback.hpp"
#include "puma_motor_msgs/msg/multi_feedback.hpp"
#include "clearpath_motor_msgs/msg/puma_feedback.hpp"
#include "clearpath_motor_msgs/msg/puma_multi_feedback.hpp"

namespace clearpath_platform
{
Expand All @@ -51,14 +51,14 @@ class PumaHardwareInterface
void drive_command(const sensor_msgs::msg::JointState msg);

bool has_new_feedback();
void feedback_callback(const puma_motor_msgs::msg::MultiFeedback::SharedPtr msg);
puma_motor_msgs::msg::MultiFeedback get_feedback();
void feedback_callback(const clearpath_motor_msgs::msg::PumaMultiFeedback::SharedPtr msg);
clearpath_motor_msgs::msg::PumaMultiFeedback get_feedback();

private:
rclcpp::Publisher<sensor_msgs::msg::JointState>::SharedPtr pub_cmd_;
rclcpp::Subscription<puma_motor_msgs::msg::MultiFeedback>::SharedPtr sub_feedback_;
rclcpp::Subscription<clearpath_motor_msgs::msg::PumaMultiFeedback>::SharedPtr sub_feedback_;

puma_motor_msgs::msg::MultiFeedback feedback_;
clearpath_motor_msgs::msg::PumaMultiFeedback feedback_;
std::atomic_bool has_feedback_;
};

Expand Down
2 changes: 1 addition & 1 deletion clearpath_platform/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,12 +21,12 @@
<depend>controller_interface</depend>
<depend>controller_manager</depend>
<depend>controller_manager_msgs</depend>
<depend>clearpath_motor_msgs</depend>
<depend>clearpath_platform_msgs</depend>
<depend>hardware_interface</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
<depend>pluginlib</depend>
<depend>puma_motor_msgs</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>std_msgs</depend>
Expand Down
8 changes: 4 additions & 4 deletions clearpath_platform/src/puma/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ using clearpath_platform::PumaHardwareInterface;
PumaHardwareInterface::PumaHardwareInterface(std::string node_name)
: Node(node_name)
{
sub_feedback_ = create_subscription<puma_motor_msgs::msg::MultiFeedback>(
sub_feedback_ = create_subscription<clearpath_motor_msgs::msg::PumaMultiFeedback>(
"platform/puma/feedback",
rclcpp::SensorDataQoS(),
std::bind(&PumaHardwareInterface::feedback_callback, this, std::placeholders::_1));
Expand All @@ -52,7 +52,7 @@ PumaHardwareInterface::PumaHardwareInterface(std::string node_name)
*
* @param msg
*/
void PumaHardwareInterface::feedback_callback(const puma_motor_msgs::msg::MultiFeedback::SharedPtr msg)
void PumaHardwareInterface::feedback_callback(const clearpath_motor_msgs::msg::PumaMultiFeedback::SharedPtr msg)
{
feedback_ = *msg;
has_feedback_ = true;
Expand Down Expand Up @@ -83,9 +83,9 @@ bool PumaHardwareInterface::has_new_feedback()
/**
* @brief Get feedback
*
* @return puma_motor_msgs::msg::MultiFeedback
* @return clearpath_motor_msgs::msg::PumaMultiFeedback
*/
puma_motor_msgs::msg::MultiFeedback PumaHardwareInterface::get_feedback()
clearpath_motor_msgs::msg::PumaMultiFeedback PumaHardwareInterface::get_feedback()
{
has_feedback_ = false;
return feedback_;
Expand Down

0 comments on commit d32075b

Please sign in to comment.