Skip to content

Commit 3b68071

Browse files
committed
change bumper interface
1 parent 8bc349a commit 3b68071

2 files changed

Lines changed: 14 additions & 19 deletions

File tree

common_interfaces_cpp/include/common_interfaces_cpp/hal/bumper.hpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
#include <vector>
55
#include <string>
66
#include "rclcpp/rclcpp.hpp"
7-
#include "gazebo_msgs/msg/contacts_state.hpp"
7+
#include "ros_gz_interfaces/msg/contacts.hpp"
88

99
/* ### AUXILIARY FUNCTIONS ### */
1010

@@ -21,7 +21,7 @@ class BumperData {
2121
std::string to_string() const;
2222
};
2323

24-
BumperData contactsToBumperData(const std::vector<gazebo_msgs::msg::ContactsState>& contacts);
24+
BumperData contactsToBumperData(const std::vector<ros_gz_interfaces::msg::Contacts>& contacts);
2525

2626
/* ### HAL INTERFACE ### */
2727
class BumperNode : public rclcpp::Node {
@@ -30,13 +30,13 @@ class BumperNode : public rclcpp::Node {
3030
BumperData getBumperData() const;
3131

3232
private:
33-
void right_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact);
34-
void center_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact);
35-
void left_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact);
33+
void right_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact);
34+
void center_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact);
35+
void left_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact);
3636

3737
std::vector<std::string> topics;
38-
std::vector<rclcpp::Subscription<gazebo_msgs::msg::ContactsState>::SharedPtr> subs_;
39-
std::vector<gazebo_msgs::msg::ContactsState> contact_states_;
38+
std::vector<rclcpp::Subscription<ros_gz_interfaces::msg::Contacts>::SharedPtr> subs_;
39+
std::vector<ros_gz_interfaces::msg::Contacts> contact_states_;
4040
};
4141

4242
#endif

common_interfaces_cpp/src/hal/bumper.cpp

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,11 @@ std::string BumperData::to_string() const {
1414
return oss.str();
1515
}
1616

17-
BumperData contactsToBumperData(const std::vector<gazebo_msgs::msg::ContactsState>& contacts) {
17+
BumperData contactsToBumperData(const std::vector<ros_gz_interfaces::msg::Contacts>& contacts) {
1818
BumperData bumper_data;
1919

2020
for (size_t i = 0; i < contacts.size(); ++i) {
21-
if (contacts[i].states.size() > 0) {
21+
if (contacts[i].contacts.size() > 0) {
2222
bumper_data.state = 1;
2323
bumper_data.bumper = i;
2424
break;
@@ -31,33 +31,28 @@ BumperData contactsToBumperData(const std::vector<gazebo_msgs::msg::ContactsStat
3131
BumperNode::BumperNode(const std::vector<std::string>& topics_list)
3232
: Node("bumper_node"), topics(topics_list), contact_states_(3) {
3333

34-
// Hardcoded for the moment to three topics
35-
// as dynamic callback creation is not trivial
36-
std::vector<std::function<void(const gazebo_msgs::msg::ContactsState::SharedPtr)>> callbacks_ = {
34+
std::vector<std::function<void(const ros_gz_interfaces::msg::Contacts::SharedPtr)>> callbacks_ = {
3735
std::bind(&BumperNode::right_callback, this, std::placeholders::_1),
3836
std::bind(&BumperNode::center_callback, this, std::placeholders::_1),
3937
std::bind(&BumperNode::left_callback, this, std::placeholders::_1)
4038
};
4139

42-
// Subscribe to all the callbacks
4340
for (size_t i = 0; i < topics.size(); ++i) {
44-
subs_.push_back(this->create_subscription<gazebo_msgs::msg::ContactsState>(
41+
subs_.push_back(this->create_subscription<ros_gz_interfaces::msg::Contacts>(
4542
topics[i], 10, callbacks_[i]
4643
));
4744
}
48-
49-
// Right, center, left
5045
}
5146

52-
void BumperNode::right_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact) {
47+
void BumperNode::right_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact) {
5348
contact_states_[0] = *contact;
5449
}
5550

56-
void BumperNode::center_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact) {
51+
void BumperNode::center_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact) {
5752
contact_states_[1] = *contact;
5853
}
5954

60-
void BumperNode::left_callback(const gazebo_msgs::msg::ContactsState::SharedPtr contact) {
55+
void BumperNode::left_callback(const ros_gz_interfaces::msg::Contacts::SharedPtr contact) {
6156
contact_states_[2] = *contact;
6257
}
6358

0 commit comments

Comments
 (0)