Skip to content

Commit

Permalink
cpplint compliant changes
Browse files Browse the repository at this point in the history
  • Loading branch information
pranavpshah committed Mar 13, 2024
1 parent 64981e4 commit cdde203
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 18 deletions.
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
#include <memory>
#include <vector>

#include "kr_mav_msgs/msg/corrections.hpp"
#include "kr_mav_msgs/msg/position_command.hpp"
#include "kr_mav_msgs/msg/so3_command.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/bool.hpp"

using namespace std::chrono_literals;

class SO3ControlTester : public rclcpp::Node
{
public:
Expand Down Expand Up @@ -58,7 +59,7 @@ bool SO3ControlTester::is_so3_cmd_publisher_active()
flag = true;
else
{
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
if(so3_cmd_sub_->get_publisher_count() > 0)
flag = true;
else
Expand Down
2 changes: 1 addition & 1 deletion kr_mav_controllers/src/pid_control_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
class PIDControlComponent : public rclcpp::Node
{
public:
PIDControlComponent(const rclcpp::NodeOptions &options);
explicit PIDControlComponent(const rclcpp::NodeOptions &options);

private:
void publishTRPYCommand(void);
Expand Down
2 changes: 1 addition & 1 deletion kr_mav_controllers/src/so3_control_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
class SO3ControlComponent : public rclcpp::Node
{
public:
SO3ControlComponent(const rclcpp::NodeOptions &options);
explicit SO3ControlComponent(const rclcpp::NodeOptions &options);

private:
void publishSO3Command();
Expand Down
2 changes: 1 addition & 1 deletion kr_mav_controllers/src/so3_trpy_control.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
class SO3TRPYControlComponent : public rclcpp::Node
{
public:
SO3TRPYControlComponent(const rclcpp::NodeOptions &options);
explicit SO3TRPYControlComponent(const rclcpp::NodeOptions &options);

private:
void publishCommand();
Expand Down
24 changes: 12 additions & 12 deletions kr_mav_controllers/test/so3_control_component_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ class SO3ControlComponentTest : public testing::Test
{
executor->add_node(tester);
spin_thread = std::thread([this]() { executor->spin(); });
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
}

// Cancel spinning of node
Expand Down Expand Up @@ -57,7 +57,7 @@ TEST_F(SO3ControlComponentTest, Test2)
{
std::cout << "Performing Test2!\n";
tester->publish_single_position_command();
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
{
std::lock_guard<std::mutex> lock(tester->mutex);
EXPECT_FALSE(tester->so3_command_received_);
Expand All @@ -73,7 +73,7 @@ TEST_F(SO3ControlComponentTest, Test3)
{
tester->publish_enable_motors(true);
tester->publish_single_position_command();
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
{
std::lock_guard<std::mutex> lock(tester->mutex);
EXPECT_FALSE(tester->so3_command_received_);
Expand All @@ -90,9 +90,9 @@ TEST_F(SO3ControlComponentTest, Test4)
tester->publish_enable_motors(true);
tester->populate_odom_msgs();
tester->publish_odom_msg(0);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
tester->publish_single_position_command();
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
Test4Data ref;
{
std::lock_guard<std::mutex> lock(tester->mutex);
Expand Down Expand Up @@ -124,12 +124,12 @@ TEST_F(SO3ControlComponentTest, Test5)
tester->populate_odom_msgs();
tester->populate_position_cmd_vector(1, 1, 2, 0, 0.1);
tester->publish_odom_msg(0);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
Test5Data ref;
for(int i = 0; i < 11; i++)
{
tester->publish_position_command(i);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
{
std::lock_guard<std::mutex> lock(tester->mutex);
EXPECT_TRUE(tester->so3_command_received_);
Expand Down Expand Up @@ -161,12 +161,12 @@ TEST_F(SO3ControlComponentTest, Test6)
tester->populate_odom_msgs();
tester->populate_position_cmd_vector(2, 3, 5, 7, 0.2);
tester->publish_odom_msg(1);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
Test6Data ref;
for(int i = 0; i < 11; i++)
{
tester->publish_position_command(i);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
{
std::lock_guard<std::mutex> lock(tester->mutex);
EXPECT_TRUE(tester->so3_command_received_);
Expand Down Expand Up @@ -201,14 +201,14 @@ TEST_F(SO3ControlComponentTest, Test7)
float kf_corr = 1.0f;
float ang_corr[2] = {0.2f, 0.3f};
tester->publish_corrections(kf_corr, ang_corr);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
tester->publish_odom_msg(2);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
Test7Data ref;
for(int i = 0; i < 11; i++)
{
tester->publish_position_command(i);
rclcpp::sleep_for(1s);
rclcpp::sleep_for(std::chrono::seconds(1));
{
std::lock_guard<std::mutex> lock(tester->mutex);
EXPECT_TRUE(tester->so3_command_received_);
Expand Down

0 comments on commit cdde203

Please sign in to comment.