Skip to content

Instantly share code, notes, and snippets.

@alesolano
Last active June 21, 2019 07:12
Show Gist options
  • Save alesolano/d96cf107b851b456ebd58949bbb23ccb to your computer and use it in GitHub Desktop.
Save alesolano/d96cf107b851b456ebd58949bbb23ccb to your computer and use it in GitHub Desktop.
#include "rclcpp/rclcpp.hpp"
#include "hrim_actuator_rotaryservo_msgs/msg/state_rotary_servo.hpp"
using std::placeholders::_1;
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber(): Node("minimal_subscriber"),
called(false)
{
sub_ = this->create_subscription<hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo>(
"/hrim_actuator_rotaryservo_000000000001/state_axis1",
rclcpp::SensorDataQoS(),
std::bind(&MinimalSubscriber::minimal_callback, this, _1));
}
bool called;
private:
void minimal_callback(const hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo::UniquePtr msg)
{
RCLCPP_INFO(this->get_logger(), "Position: %f", msg->position);
called = true;
}
rclcpp::Subscription<hrim_actuator_rotaryservo_msgs::msg::StateRotaryServo>::SharedPtr sub_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<MinimalSubscriber>();
// Just run the callback once
while (!node->called){
rclcpp::spin_some(node);
}
rclcpp::shutdown();
return 0;
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment