Skip to content

Commit 820919b

Browse files
SteveMacenskienricosutera
authored andcommitted
fix some new build warnings from sync (ros-navigation#3674)
* fix some new build warnings * fixing last issue * Update navigate_through_poses_action.hpp * adding unsigned int to tests * all to unsigned shorts * test new warning resolution * Update * convert unsigned shorts to uint16_t for linter Signed-off-by: enricosutera <[email protected]>
1 parent dae87ce commit 820919b

File tree

7 files changed

+19
-17
lines changed

7 files changed

+19
-17
lines changed

nav2_behavior_tree/include/nav2_behavior_tree/plugins/action/navigate_through_poses_action.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#define NAV2_BEHAVIOR_TREE__PLUGINS__ACTION__NAVIGATE_THROUGH_POSES_ACTION_HPP_
1717

1818
#include <string>
19+
#include <vector>
1920

2021
#include "geometry_msgs/msg/point.hpp"
2122
#include "geometry_msgs/msg/quaternion.hpp"
@@ -74,7 +75,8 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
7475
{
7576
return providedBasicPorts(
7677
{
77-
BT::InputPort<geometry_msgs::msg::PoseStamped>("goals", "Destinations to plan through"),
78+
BT::InputPort<std::vector<geometry_msgs::msg::PoseStamped>>(
79+
"goals", "Destinations to plan through"),
7880
BT::InputPort<std::string>("behavior_tree", "Behavior tree to run"),
7981
BT::OutputPort<ActionResult::_error_code_type>(
8082
"error_code_id", "The navigate through poses error code"),

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/are_error_codes_present_condition.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -34,14 +34,14 @@ class AreErrorCodesPresent : public BT::ConditionNode
3434
const BT::NodeConfiguration & conf)
3535
: BT::ConditionNode(condition_name, conf)
3636
{
37-
getInput<std::set<unsigned short>>("error_codes_to_check", error_codes_to_check_); //NOLINT
37+
getInput<std::set<uint16_t>>("error_codes_to_check", error_codes_to_check_); //NOLINT
3838
}
3939

4040
AreErrorCodesPresent() = delete;
4141

4242
BT::NodeStatus tick()
4343
{
44-
getInput<unsigned short>("error_code", error_code_); //NOLINT
44+
getInput<uint16_t>("error_code", error_code_); //NOLINT
4545

4646
if (error_codes_to_check_.find(error_code_) != error_codes_to_check_.end()) {
4747
return BT::NodeStatus::SUCCESS;
@@ -54,14 +54,14 @@ class AreErrorCodesPresent : public BT::ConditionNode
5454
{
5555
return
5656
{
57-
BT::InputPort<unsigned short>("error_code", "The active error codes"), //NOLINT
58-
BT::InputPort<std::set<unsigned short>>("error_codes_to_check", "Error codes to check")//NOLINT
57+
BT::InputPort<uint16_t>("error_code", "The active error codes"), //NOLINT
58+
BT::InputPort<std::set<uint16_t>>("error_codes_to_check", "Error codes to check")//NOLINT
5959
};
6060
}
6161

6262
protected:
63-
unsigned short error_code_; //NOLINT
64-
std::set<unsigned short> error_codes_to_check_; //NOLINT
63+
uint16_t error_code_; //NOLINT
64+
std::set<uint16_t> error_codes_to_check_; //NOLINT
6565
};
6666

6767
} // namespace nav2_behavior_tree

nav2_behavior_tree/test/plugins/condition/test_are_error_codes_present.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,8 @@ class AreErrorCodesPresentFixture : public nav2_behavior_tree::BehaviorTreeTestF
2727
using ActionGoal = Action::Goal;
2828
void SetUp()
2929
{
30-
int error_code = ActionGoal::NONE;
31-
std::set<unsigned short> error_codes_to_check = {ActionGoal::UNKNOWN}; //NOLINT
30+
uint16_t error_code = ActionGoal::NONE;
31+
std::set<uint16_t> error_codes_to_check = {ActionGoal::UNKNOWN}; //NOLINT
3232
config_->blackboard->set("error_code", error_code);
3333
config_->blackboard->set("error_codes_to_check", error_codes_to_check);
3434

@@ -58,7 +58,7 @@ std::shared_ptr<BT::Tree> AreErrorCodesPresentFixture::tree_ = nullptr;
5858

5959
TEST_F(AreErrorCodesPresentFixture, test_condition)
6060
{
61-
std::map<int, BT::NodeStatus> error_to_status_map = {
61+
std::map<uint16_t, BT::NodeStatus> error_to_status_map = {
6262
{ActionGoal::NONE, BT::NodeStatus::FAILURE},
6363
{ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS},
6464
};

nav2_behavior_tree/test/plugins/condition/test_would_a_controller_recovery_help.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ class WouldAControllerRecoveryHelpFixture : public nav2_behavior_tree::BehaviorT
2727
using ActionGoal = Action::Goal;
2828
void SetUp()
2929
{
30-
int error_code = ActionGoal::NONE;
30+
uint16_t error_code = ActionGoal::NONE;
3131
config_->blackboard->set("error_code", error_code);
3232

3333
std::string xml_txt =
@@ -56,7 +56,7 @@ std::shared_ptr<BT::Tree> WouldAControllerRecoveryHelpFixture::tree_ = nullptr;
5656

5757
TEST_F(WouldAControllerRecoveryHelpFixture, test_condition)
5858
{
59-
std::map<int, BT::NodeStatus> error_to_status_map = {
59+
std::map<uint16_t, BT::NodeStatus> error_to_status_map = {
6060
{ActionGoal::NONE, BT::NodeStatus::FAILURE},
6161
{ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS},
6262
{ActionGoal::INVALID_CONTROLLER, BT::NodeStatus::FAILURE},

nav2_behavior_tree/test/plugins/condition/test_would_a_planner_recovery_help.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ class WouldAPlannerRecoveryHelpFixture : public nav2_behavior_tree::BehaviorTree
2727
using ActionGoal = Action::Goal;
2828
void SetUp()
2929
{
30-
int error_code = ActionGoal::NONE;
30+
uint16_t error_code = ActionGoal::NONE;
3131
config_->blackboard->set("error_code", error_code);
3232

3333
std::string xml_txt =
@@ -56,7 +56,7 @@ std::shared_ptr<BT::Tree> WouldAPlannerRecoveryHelpFixture::tree_ = nullptr;
5656

5757
TEST_F(WouldAPlannerRecoveryHelpFixture, test_condition)
5858
{
59-
std::map<int, BT::NodeStatus> error_to_status_map = {
59+
std::map<uint16_t, BT::NodeStatus> error_to_status_map = {
6060
{ActionGoal::NONE, BT::NodeStatus::FAILURE},
6161
{ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS},
6262
{ActionGoal::NO_VALID_PATH, BT::NodeStatus::SUCCESS},

nav2_behavior_tree/test/plugins/condition/test_would_a_smoother_recovery_help.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ class WouldASmootherRecoveryHelpFixture : public nav2_behavior_tree::BehaviorTre
2727
using ActionGoal = Action::Goal;
2828
void SetUp()
2929
{
30-
int error_code = ActionGoal::NONE;
30+
uint16_t error_code = ActionGoal::NONE;
3131
config_->blackboard->set("error_code", error_code);
3232

3333
std::string xml_txt =
@@ -56,7 +56,7 @@ std::shared_ptr<BT::Tree> WouldASmootherRecoveryHelpFixture::tree_ = nullptr;
5656

5757
TEST_F(WouldASmootherRecoveryHelpFixture, test_condition)
5858
{
59-
std::map<int, BT::NodeStatus> error_to_status_map = {
59+
std::map<uint16_t, BT::NodeStatus> error_to_status_map = {
6060
{ActionGoal::NONE, BT::NodeStatus::FAILURE},
6161
{ActionGoal::UNKNOWN, BT::NodeStatus::SUCCESS},
6262
{ActionGoal::TIMEOUT, BT::NodeStatus::SUCCESS},

nav2_mppi_controller/test/utils_test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -368,7 +368,7 @@ TEST(UtilsTests, SmootherTest)
368368

369369
// Check that path is smoother
370370
float smoothed_val, original_val;
371-
for (unsigned int i = 0; i != noisey_sequence.vx.shape(0); i++) {
371+
for (unsigned int i = 1; i != noisey_sequence.vx.shape(0) - 1; i++) {
372372
smoothed_val += fabs(noisey_sequence.vx(i) - 0.2);
373373
smoothed_val += fabs(noisey_sequence.vy(i) - 0.0);
374374
smoothed_val += fabs(noisey_sequence.wz(i) - 0.3);

0 commit comments

Comments
 (0)