Skip to content

Commit

Permalink
Run cpplint checks
Browse files Browse the repository at this point in the history
  • Loading branch information
NestorDP committed Aug 11, 2023
1 parent 2a04439 commit 7d2d469
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 33 deletions.
45 changes: 21 additions & 24 deletions littlebot_teleop/include/littlebot_teleop/teleop.hpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@
// Copyright 2023 Nestor Neto

// Copyright Nestor 2022

#ifndef LITTLEBOT_TELEOP_TELEOP_HPP_
#define LITTLEBOT_TELEOP_TELEOP_HPP_
#ifndef LITTLEBOT_TELEOP_INCLUDE_LITTLEBOT_TELEOP_TELEOP_HPP_
#define LITTLEBOT_TELEOP_INCLUDE_LITTLEBOT_TELEOP_TELEOP_HPP_

#include <string>
#include <sstream>
#include <chrono>
#include <chrono> // NOLINT
#include <iostream>
#include <memory>
#include <utility>
Expand All @@ -19,24 +18,22 @@
#define LITTLEBOT_TELEOP_CPP_PUBLIC __attribute__ ((visibility("default")))

namespace littlebot_teleop {
class Teleop : public rclcpp::Node {
public:
LITTLEBOT_TELEOP_CPP_PUBLIC
explicit Teleop(const rclcpp::NodeOptions & options);

protected:
void teleopPublisher(void);

private:
rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr sub_joy_;
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_twist_;
rclcpp::TimerBase::SharedPtr timer_;

float x_joy_value_;
float z_joy_value_;


};
class Teleop : public rclcpp::Node {
public:
LITTLEBOT_TELEOP_CPP_PUBLIC
explicit Teleop(const rclcpp::NodeOptions & options);

protected:
void teleopPublisher(void);

private:
rclcpp::Subscription<sensor_msgs::msg::Joy>::SharedPtr sub_joy_;
rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_twist_;
rclcpp::TimerBase::SharedPtr timer_;

float x_joy_value_;
float z_joy_value_;
};
} // namespace littlebot_teleop

#endif // LITTLEBOT_TELEOP_TELEOP_HPP_/
#endif // LITTLEBOT_TELEOP_INCLUDE_LITTLEBOT_TELEOP_TELEOP_HPP_/
18 changes: 9 additions & 9 deletions littlebot_teleop/src/teleop.cpp
Original file line number Diff line number Diff line change
@@ -1,30 +1,30 @@
// Copyright Nestor 2022-2023

// Copyright 2023 Nestor Neto

#include "littlebot_teleop/teleop.hpp"

using namespace std::chrono_literals;
using namespace std::chrono_literals; // NOLINT

namespace littlebot_teleop {
Teleop::Teleop(const rclcpp::NodeOptions & options)
: Node("littlebot_teleop","", options){
: Node("littlebot_teleop" , "", options) {

auto joy_callback =
[this](sensor_msgs::msg::Joy::ConstSharedPtr joy) -> void {
z_joy_value_ = joy->axes[0];
x_joy_value_ = joy->axes[3];
};

sub_joy_ =
create_subscription<sensor_msgs::msg::Joy>("joy", 10, joy_callback);

pub_twist_ =
pub_twist_ =
this->create_publisher<geometry_msgs::msg::Twist>(
"joy_teleop/cmd_vel",
10);


timer_ = create_wall_timer(100ms, std::bind(&Teleop::teleopPublisher, this));
timer_ =
create_wall_timer(100ms, std::bind(&Teleop::teleopPublisher, this));
}

void Teleop::teleopPublisher() {
Expand All @@ -36,4 +36,4 @@ namespace littlebot_teleop {

} // namespace littlebot_teleop

RCLCPP_COMPONENTS_REGISTER_NODE(littlebot_teleop::Teleop)
RCLCPP_COMPONENTS_REGISTER_NODE(littlebot_teleop::Teleop)

0 comments on commit 7d2d469

Please sign in to comment.