Fix linting errors

This commit is contained in:
Christophe Bedard 2019-06-05 15:35:46 +02:00
parent 6cce113f04
commit 33f227b772
27 changed files with 668 additions and 563 deletions

View file

@ -3,47 +3,47 @@
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
class PongNode : public rclcpp::Node
{
public:
PongNode(rclcpp::NodeOptions options) : Node("pong_node", options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"ping",
rclcpp::QoS(10),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
"pong",
rclcpp::QoS(10));
}
explicit PongNode(rclcpp::NodeOptions options)
: Node("pong_node", options)
{
sub_ = this->create_subscription<std_msgs::msg::String>(
"ping",
rclcpp::QoS(10),
std::bind(&PongNode::callback, this, std::placeholders::_1));
pub_ = this->create_publisher<std_msgs::msg::String>(
"pong",
rclcpp::QoS(10));
}
private:
void callback(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
auto next_msg = std::make_shared<std_msgs::msg::String>();
next_msg->data = "some random pong string";
pub_->publish(*next_msg);
rclcpp::shutdown();
}
void callback(const std_msgs::msg::String::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "[output] %s", msg->data.c_str());
auto next_msg = std::make_shared<std_msgs::msg::String>();
next_msg->data = "some random pong string";
pub_->publish(*next_msg);
rclcpp::shutdown();
}
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr sub_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
};
int main(int argc, char* argv[])
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node);
rclcpp::executors::SingleThreadedExecutor exec;
auto pong_node = std::make_shared<PongNode>(rclcpp::NodeOptions());
exec.add_node(pong_node);
printf("spinning\n");
exec.spin();
printf("spinning\n");
exec.spin();
// Will actually be called inside the node's callback
rclcpp::shutdown();
return 0;
// Will actually be called inside the node's callback
rclcpp::shutdown();
return 0;
}