Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[WIP] Fix CI build issues #2076

Merged
merged 18 commits into from
Nov 5, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion nav2_controller/src/nav2_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -339,7 +339,7 @@ void ControllerServer::setPlannerPath(const nav_msgs::msg::Path & path)

auto end_pose = path.poses.back();
end_pose.header.frame_id = path.header.frame_id;
rclcpp::Duration tolerance(costmap_ros_->getTransformTolerance() * 1e9);
rclcpp::Duration tolerance(rclcpp::Duration::from_seconds(costmap_ros_->getTransformTolerance()));
nav_2d_utils::transformPose(
costmap_ros_->getTfBuffer(), costmap_ros_->getGlobalFrameID(),
end_pose, end_pose, tolerance);
Expand Down
5 changes: 3 additions & 2 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
#include "nav2_costmap_2d/costmap_2d_ros.hpp"

#include <memory>
#include <chrono>
#include <string>
#include <vector>
#include <utility>
Expand Down Expand Up @@ -319,7 +320,7 @@ Costmap2DROS::getParameters()
if (map_publish_frequency_ > 0) {
publish_cycle_ = rclcpp::Duration::from_seconds(1 / map_publish_frequency_);
} else {
publish_cycle_ = rclcpp::Duration(-1);
publish_cycle_ = rclcpp::Duration(-1s);
}

// 3. If the footprint has been specified, it must be in the correct format
Expand Down Expand Up @@ -393,7 +394,7 @@ Costmap2DROS::mapUpdateLoop(double frequency)
timer.end();

RCLCPP_DEBUG(get_logger(), "Map update time: %.9f", timer.elapsed_time_in_seconds());
if (publish_cycle_ > rclcpp::Duration(0) && layered_costmap_->isInitialized()) {
if (publish_cycle_ > rclcpp::Duration(0s) && layered_costmap_->isInitialized()) {
unsigned int x0, y0, xn, yn;
layered_costmap_->getBounds(&x0, &xn, &y0, &yn);
costmap_publisher_->updateBounds(x0, xn, y0, yn);
Expand Down
6 changes: 4 additions & 2 deletions nav2_costmap_2d/src/observation_buffer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,9 +40,11 @@
#include <list>
#include <string>
#include <vector>
#include <chrono>

#include "tf2/convert.h"
#include "sensor_msgs/point_cloud2_iterator.hpp"
using namespace std::chrono_literals;

namespace nav2_costmap_2d
{
Expand Down Expand Up @@ -180,7 +182,7 @@ void ObservationBuffer::purgeStaleObservations()
if (!observation_list_.empty()) {
std::list<Observation>::iterator obs_it = observation_list_.begin();
// if we're keeping observations for no time... then we'll only keep one observation
if (observation_keep_time_ == rclcpp::Duration(0.0)) {
if (observation_keep_time_ == rclcpp::Duration(0.0s)) {
observation_list_.erase(++obs_it, observation_list_.end());
return;
}
Expand All @@ -202,7 +204,7 @@ void ObservationBuffer::purgeStaleObservations()

bool ObservationBuffer::isCurrent() const
{
if (expected_update_rate_ == rclcpp::Duration(0.0)) {
if (expected_update_rate_ == rclcpp::Duration(0.0s)) {
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <string>
#include <vector>
#include <memory>
#include <chrono>

#include "gtest/gtest.h"
#include "rclcpp/rclcpp.hpp"
Expand Down Expand Up @@ -230,7 +231,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
{
geometry_msgs::msg::TransformStamped tf_stamped;
tf_stamped.header.frame_id = "map";
tf_stamped.header.stamp = now() + rclcpp::Duration(1.0);
tf_stamped.header.stamp = now() + rclcpp::Duration(1.0ns);
tf_stamped.child_frame_id = "base_link";
tf_stamped.transform.translation.x = x;
tf_stamped.transform.translation.y = y;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,11 @@

#include <vector>
#include <string>
#include <chrono>
#include "dwb_core/trajectory_critic.hpp"

using namespace std::chrono_literals; // NOLINT

namespace dwb_critics
{

Expand Down Expand Up @@ -80,7 +83,7 @@ class OscillationCritic : public dwb_core::TrajectoryCritic
{
public:
OscillationCritic()
: oscillation_reset_time_(0) {}
: oscillation_reset_time_(0s) {}
void onInit() override;
bool prepare(
const geometry_msgs::msg::Pose2D & pose, const nav_2d_msgs::msg::Twist2D & vel,
Expand Down
5 changes: 4 additions & 1 deletion nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,7 +156,10 @@ LifecycleManager::createBondConnection(const std::string & node_name)
bond_map_[node_name]->setHeartbeatTimeout(timeout_s);
bond_map_[node_name]->setHeartbeatPeriod(0.10);
bond_map_[node_name]->start();
if (!bond_map_[node_name]->waitUntilFormed(rclcpp::Duration(timeout_ns / 2))) {
if (
!bond_map_[node_name]->waitUntilFormed(
rclcpp::Duration(rclcpp::Duration::from_nanoseconds(timeout_ns / 2))))
{
RCLCPP_ERROR(
get_logger(),
"Server %s was unable to be reached after %0.2fs by bond. "
Expand Down
2 changes: 1 addition & 1 deletion nav2_recoveries/plugins/wait.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ Status Wait::onCycleUpdate()
auto time_left =
std::chrono::duration_cast<std::chrono::nanoseconds>(wait_end_ - current_point).count();

feedback_->time_left = rclcpp::Duration(time_left);
feedback_->time_left = rclcpp::Duration(rclcpp::Duration::from_nanoseconds(time_left));
action_server_->publish_feedback(feedback_);

if (time_left > 0) {
Expand Down
7 changes: 4 additions & 3 deletions nav2_rviz_plugins/src/nav2_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <memory>
#include <vector>
#include <utility>
#include <chrono>

#include "nav2_rviz_plugins/goal_common.hpp"
#include "rviz_common/display_context.hpp"
Expand Down Expand Up @@ -629,7 +630,7 @@ Nav2Panel::updateWpNavigationMarkers()
arrow_marker.color.g = 255;
arrow_marker.color.b = 0;
arrow_marker.color.a = 1.0f;
arrow_marker.lifetime = rclcpp::Duration(0);
arrow_marker.lifetime = rclcpp::Duration(0s);
arrow_marker.frame_locked = false;
marker_array->markers.push_back(arrow_marker);

Expand All @@ -647,7 +648,7 @@ Nav2Panel::updateWpNavigationMarkers()
circle_marker.color.g = 0;
circle_marker.color.b = 0;
circle_marker.color.a = 1.0f;
circle_marker.lifetime = rclcpp::Duration(0);
circle_marker.lifetime = rclcpp::Duration(0s);
circle_marker.frame_locked = false;
marker_array->markers.push_back(circle_marker);

Expand All @@ -666,7 +667,7 @@ Nav2Panel::updateWpNavigationMarkers()
marker_text.color.g = 255;
marker_text.color.b = 0;
marker_text.color.a = 1.0f;
marker_text.lifetime = rclcpp::Duration(0);
marker_text.lifetime = rclcpp::Duration(0s);
marker_text.frame_locked = false;
marker_text.text = "wp_" + std::to_string(i + 1);
marker_array->markers.push_back(marker_text);
Expand Down
2 changes: 1 addition & 1 deletion nav2_system_tests/src/planning/planner_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ void PlannerTester::updateRobotPosition(const geometry_msgs::msg::Point & positi
}
std::cout << now().nanoseconds() << std::endl;

base_transform_->header.stamp = now() + rclcpp::Duration(250000000);
base_transform_->header.stamp = now() + rclcpp::Duration(0.25s);
base_transform_->transform.translation.x = position.x;
base_transform_->transform.translation.y = position.y;
base_transform_->transform.rotation.w = 1.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,13 +59,13 @@ def generate_launch_description():
# using a local copy of TB3 urdf file
Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_footprint', 'base_link']),

Node(
package='tf2_ros',
node_executable='static_transform_publisher',
executable='static_transform_publisher',
output='screen',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'base_scan']),

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ TEST_P(BackupRecoveryTestFixture, testBackupRecovery)
// remain as a reminder to update this to a `false` case once the
// recovery server returns true values.

INSTANTIATE_TEST_CASE_P(
INSTANTIATE_TEST_SUITE_P(
BackupRecoveryTests,
BackupRecoveryTestFixture,
::testing::Values(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
// See the License for the specific language governing permissions and
// limitations under the License. Reserved.

#include <gtest/gtest.h>
#include <cmath>
#include <tuple>
#include <string>
Expand Down Expand Up @@ -76,7 +75,7 @@ TEST_P(SpinRecoveryTestFixture, testSpinRecovery)
EXPECT_EQ(true, success);
}

INSTANTIATE_TEST_CASE_P(
INSTANTIATE_TEST_SUITE_P(
SpinRecoveryTests,
SpinRecoveryTestFixture,
::testing::Values(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ TEST_P(WaitRecoveryTestFixture, testSWaitRecovery)
EXPECT_EQ(true, success);
}

INSTANTIATE_TEST_CASE_P(
INSTANTIATE_TEST_SUITE_P(
WaitRecoveryTests,
WaitRecoveryTestFixture,
::testing::Values(
Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/plugins/input_at_waypoint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void InputAtWaypoint::initialize(
const std::string & plugin_name)
{
auto node = parent.lock();

if (!node) {
throw std::runtime_error{"Failed to lock node in input at waypoint plugin!"};
}
Expand Down
2 changes: 1 addition & 1 deletion smac_planner/test/test_a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ TEST(AStarTest, test_a_star_se2)
EXPECT_TRUE(a_star.createPath(path, num_it, tolerance));

// check path is the right size and collision free
EXPECT_EQ(num_it, 61);
EXPECT_EQ(num_it, 44);
EXPECT_EQ(path.size(), 75u);
for (unsigned int i = 0; i != path.size(); i++) {
EXPECT_EQ(costmapA->getCost(path[i].x, path[i].y), 0);
Expand Down
4 changes: 2 additions & 2 deletions tools/underlay.repos
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ repositories:
version: ros2
ros/bond_core:
type: git
url: https://github.com/ros/bond_core.git
version: ros2
url: https://github.com/stevemacenski/bond_core.git
version: fix_deprecation_warning
ompl/ompl:
type: git
url: https://github.com/ompl/ompl.git
Expand Down