Skip to content
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 .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -26,5 +26,5 @@ before_install:
script:
- docker run --name nav2_bash --rm -d -i -t nav2:latest bash -l
- docker exec nav2_bash bash -c '. /ros2_ws/navigation2_ws/install/setup.bash &&
colcon test --packages-skip nav2_tasks'
colcon test --ctest-args " -V" --packages-skip nav2_tasks'
- docker exec nav2_bash bash -c "colcon test-result --verbose"
11 changes: 7 additions & 4 deletions nav2_robot/include/nav2_robot/robot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,11 @@ class Robot
explicit Robot(rclcpp::Node::SharedPtr & node);
Robot() = delete;

bool getCurrentPose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose);
bool getCurrentVelocity(nav_msgs::msg::Odometry::SharedPtr & robot_velocity);
bool getGlobalLocalizerPose(
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose);
Copy link
Copy Markdown

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is such a long typename. Adding the line using geometry_msgs::msg::PoseWithCovarianceStamped in the class would let you shorten these names here and in the CPP file.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I won't be using the using in this PR to be consistent. However, you are correct we should consider using.

bool getCurrentPose(
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose);
bool getOdometry(nav_msgs::msg::Odometry::SharedPtr & robot_odom);
std::string getName();
void sendVelocity(geometry_msgs::msg::Twist twist);

Expand All @@ -52,8 +55,8 @@ class Robot
// The current pose as received from the Pose subscription
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr current_pose_;

// The current velocity as received from the Odometry subscription
nav_msgs::msg::Odometry::SharedPtr current_velocity_;
// The odometry as received from the Odometry subscription
nav_msgs::msg::Odometry::SharedPtr current_odom_;

// Whether the subscriptions have been received
bool initial_pose_received_;
Expand Down
17 changes: 13 additions & 4 deletions nav2_robot/src/robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,15 @@ Robot::onPoseReceived(const geometry_msgs::msg::PoseWithCovarianceStamped::Share
void
Robot::onOdomReceived(const nav_msgs::msg::Odometry::SharedPtr msg)
{
current_velocity_ = msg;
current_odom_ = msg;
if (!initial_odom_received_) {
initial_odom_received_ = true;
}
}

bool
Robot::getCurrentPose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose)
Robot::getGlobalLocalizerPose(
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose)
{
if (!initial_pose_received_) {
RCLCPP_WARN(node_->get_logger(),
Expand All @@ -66,16 +67,24 @@ Robot::getCurrentPose(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr &
return true;
}

// TODO(mhpanah): We should get current pose from transforms.
bool
Robot::getCurrentVelocity(nav_msgs::msg::Odometry::SharedPtr & robot_velocity)
Robot::getCurrentPose(
geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr & robot_pose)
{
return getGlobalLocalizerPose(robot_pose);
}

bool
Robot::getOdometry(nav_msgs::msg::Odometry::SharedPtr & robot_odom)
{
if (!initial_odom_received_) {
RCLCPP_WARN(node_->get_logger(),
"Robot: Can't return current velocity: Initial odometry not yet received.");
return false;
}

robot_velocity = current_velocity_;
robot_odom = current_odom_;
return true;
}

Expand Down
4 changes: 2 additions & 2 deletions nav2_robot/test/test_robot_class.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,11 +141,11 @@ TEST_F(TestRobotClass, getPoseTest)
EXPECT_EQ(*currentPose, testPose_);
}

TEST_F(TestRobotClass, getVelocityTest)
TEST_F(TestRobotClass, getOdometryTest)
{
auto currentOdom = std::make_shared<nav_msgs::msg::Odometry>();
rclcpp::Rate r(10);
while (!(robot_->getCurrentVelocity(currentOdom))) {
while (!(robot_->getOdometry(currentOdom))) {
publishOdom();
rclcpp::spin_some(node_);
r.sleep();
Expand Down