-
Notifications
You must be signed in to change notification settings - Fork 0
Improve robotic_manipulation_node stability #8
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
Merged
Merged
Changes from 3 commits
Commits
Show all changes
4 commits
Select commit
Hold shift + click to select a range
81492fb
Add waiting for /clock message
knicked 806576d
Add /reset_manipulator service
knicked cc5dd94
Revert header updates for backward compatibility with humble
knicked e08670f
Move the initialization code from the constructor to a separate method
knicked File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,8 +1,13 @@ | ||
#include "robotic_manipulation/arm_controller.h" | ||
|
||
#include <rosgraph_msgs/msg/clock.hpp> | ||
|
||
ArmController::ArmController() { | ||
m_node = rclcpp::Node::make_shared("arm_controller"); | ||
m_node->set_parameter(rclcpp::Parameter("use_sim_time", true)); | ||
|
||
WaitForClockMessage(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Not sure if a constructor is the best place to put a blocking call. |
||
|
||
m_executor.add_node(m_node); | ||
m_spinner = std::thread([this]() { m_executor.spin(); }); | ||
|
||
|
@@ -41,21 +46,25 @@ geometry_msgs::msg::Pose ArmController::CalculatePose(double x, double y, | |
|
||
bool ArmController::MoveThroughWaypoints(const std::vector<geometry_msgs::msg::Pose>& waypoints) { | ||
auto logger = m_node->get_logger(); | ||
moveit_msgs::msg::RobotTrajectory trajectory; | ||
if (m_pandaArm->computeCartesianPath(waypoints, 0.01, 0.0, trajectory) == | ||
-1) { | ||
RCLCPP_ERROR(logger, | ||
"MoveThroughWaypoints: Failed to compute Cartesian path"); | ||
return false; | ||
} | ||
|
||
while (m_pandaArm->execute(trajectory) != | ||
moveit::core::MoveItErrorCode::SUCCESS) { | ||
RCLCPP_ERROR(logger, "MoveThroughWaypoints: Failed to execute trajectory"); | ||
return false; | ||
const int NumTries = 10; | ||
for (int i = 0; i < NumTries; i++) { | ||
moveit_msgs::msg::RobotTrajectory trajectory; | ||
if (m_pandaArm->computeCartesianPath(waypoints, 0.01, 0.0, trajectory) == | ||
-1) { | ||
RCLCPP_ERROR(logger, | ||
"MoveThroughWaypoints: Failed to compute Cartesian path"); | ||
continue; | ||
} | ||
|
||
if (m_pandaArm->execute(trajectory) == moveit::core::MoveItErrorCode::SUCCESS) { | ||
return true; | ||
} | ||
RCLCPP_ERROR(logger, "MoveThroughWaypoints: Failed to execute trajectory, trying again..."); | ||
} | ||
|
||
return true; | ||
|
||
RCLCPP_ERROR(logger, "MoveThroughWaypoints: Failed to execute trajectory after %d tries", NumTries); | ||
return false; | ||
} | ||
|
||
void ArmController::Open() { | ||
|
@@ -93,13 +102,29 @@ std::vector<double> ArmController::CaptureJointValues() { | |
return m_pandaArm->getCurrentJointValues(); | ||
} | ||
|
||
void ArmController::SetJointValues(std::vector<double> const &jointValues) { | ||
bool ArmController::SetJointValues(std::vector<double> const &jointValues) { | ||
m_pandaArm->setJointValueTarget(jointValues); | ||
if (m_pandaArm->move() != moveit::core::MoveItErrorCode::SUCCESS) { | ||
RCLCPP_ERROR(m_node->get_logger(), "Failed to set joint values"); | ||
return false; | ||
} | ||
return true; | ||
} | ||
|
||
void ArmController::SetReferenceFrame(std::string const &frame) { | ||
m_pandaArm->setPoseReferenceFrame(frame); | ||
} | ||
|
||
void ArmController::WaitForClockMessage() { | ||
bool clock_received = false; | ||
auto qos = rclcpp::QoS(rclcpp::KeepLast(1)); | ||
qos.best_effort(); | ||
auto subscription = m_node->create_subscription<rosgraph_msgs::msg::Clock>( | ||
"/clock", qos, [&] (rosgraph_msgs::msg::Clock::SharedPtr) { | ||
clock_received = true; | ||
}); | ||
while (!clock_received) { | ||
rclcpp::spin_some(m_node); | ||
} | ||
subscription.reset(); | ||
} |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Out of the scope of this change: some consistency with
const T &
vs.T const &
would be an added value.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Please see my latest comment