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

Bug fixes in main branch #362

Merged
merged 6 commits into from
Feb 23, 2021
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
Original file line number Diff line number Diff line change
Expand Up @@ -137,8 +137,8 @@ class MoveItControllerHandle
*
* Return true if the execution is complete (whether successful or not).
* Return false if timeout was reached.
* If timeout is 0 (default argument), wait until the execution is complete (no timeout). */
virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(0.0)) = 0;
* If timeout is -1 (default argument), wait until the execution is complete (no timeout). */
virtual bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(-1)) = 0;

/** \brief Return the execution status of the last trajectory sent to the controller. */
virtual ExecutionStatus getLastExecutionStatus() = 0;
Expand Down
22 changes: 5 additions & 17 deletions moveit_core/robot_trajectory/src/robot_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -223,9 +223,6 @@ void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& t
const std::vector<std::string>& joint_filter) const
{
trajectory = moveit_msgs::msg::RobotTrajectory();

builtin_interfaces::msg::Time stamp = rclcpp::Clock(RCL_ROS_TIME).now();

if (waypoints_.empty())
return;
const std::vector<const moveit::core::JointModel*>& jnts =
Expand Down Expand Up @@ -258,27 +255,24 @@ void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& t
if (!onedof.empty())
{
trajectory.joint_trajectory.header.frame_id = robot_model_->getModelFrame();
trajectory.joint_trajectory.header.stamp = stamp;
trajectory.joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
Copy link
Member

Choose a reason for hiding this comment

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

Looking at the documentation for rclcpp::Time, it looks like the default is RCL_SYSTEM_TIME. What's the reason for something different here?

Copy link
Member

@henningkayser henningkayser Feb 17, 2021

Choose a reason for hiding this comment

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

RCL_ROS_TIME is default for node time as it should be able to support simulation and is therefore mostly used for messages. It's also the equivalent for the old ros::Time while system time uses the system clock directly. See https://design.ros2.org/articles/clock_and_time.html for background on time sources.

trajectory.joint_trajectory.points.resize(waypoints_.size());
}

if (!mdof.empty())
{
trajectory.multi_dof_joint_trajectory.header.frame_id = robot_model_->getModelFrame();
trajectory.multi_dof_joint_trajectory.header.stamp = stamp;
trajectory.multi_dof_joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
henningkayser marked this conversation as resolved.
Show resolved Hide resolved
trajectory.multi_dof_joint_trajectory.points.resize(waypoints_.size());
}

static const rclcpp::Duration ZERO_DURATION(0.0);
double total_time = 0.0;
rclcpp::Duration dur_total(0, 0);
for (std::size_t i = 0; i < waypoints_.size(); ++i)
{
if (duration_from_previous_.size() > i)
total_time += duration_from_previous_[i];

dur_total = rclcpp::Duration(1, 0) * total_time;

if (!onedof.empty())
{
trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
Expand Down Expand Up @@ -310,8 +304,7 @@ void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& t
trajectory.joint_trajectory.points[i].effort.clear();

if (duration_from_previous_.size() > i)

trajectory.joint_trajectory.points[i].time_from_start = dur_total;
trajectory.joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
else
trajectory.joint_trajectory.points[i].time_from_start = ZERO_DURATION;
}
Expand Down Expand Up @@ -353,7 +346,7 @@ void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& t
}
}
if (duration_from_previous_.size() > i)
trajectory.multi_dof_joint_trajectory.points[i].time_from_start = dur_total;
trajectory.multi_dof_joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
else
trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ZERO_DURATION;
}
Expand All @@ -364,19 +357,15 @@ void RobotTrajectory::setRobotTrajectoryMsg(const moveit::core::RobotState& refe
const trajectory_msgs::msg::JointTrajectory& trajectory)
{
// make a copy just in case the next clear() removes the memory for the reference passed in

const moveit::core::RobotState& copy = reference_state;
clear();
std::size_t state_count = trajectory.points.size();
rclcpp::Time last_time_stamp = trajectory.header.stamp;
rclcpp::Time this_time_stamp = last_time_stamp;

rclcpp::Time traj_stamp = trajectory.header.stamp;
rclcpp::Duration dur_from_start(0, 0);

for (std::size_t i = 0; i < state_count; ++i)
{
this_time_stamp = traj_stamp + trajectory.points[i].time_from_start;
this_time_stamp = rclcpp::Time(trajectory.header.stamp) + trajectory.points[i].time_from_start;
moveit::core::RobotStatePtr st(new moveit::core::RobotState(copy));
st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
if (!trajectory.points[i].velocities.empty())
Expand All @@ -393,7 +382,6 @@ void RobotTrajectory::setRobotTrajectoryMsg(const moveit::core::RobotState& refe
void RobotTrajectory::setRobotTrajectoryMsg(const moveit::core::RobotState& reference_state,
const moveit_msgs::msg::RobotTrajectory& trajectory)
{
geometry_msgs::msg::TransformStamped tf_stamped;
// make a copy just in case the next clear() removes the memory for the reference passed in
const moveit::core::RobotState& copy = reference_state;
clear();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,15 +139,15 @@ class ActionBasedControllerHandle : public ActionBasedControllerHandleBase
virtual void
controllerDoneCallback(const typename rclcpp_action::ClientGoalHandle<T>::WrappedResult& wrapped_result) = 0;

bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(0)) override
bool waitForExecution(const rclcpp::Duration& timeout = rclcpp::Duration(-1)) override
{
std::promise<bool> result_callback_done;
auto result_callback_done = std::make_shared<std::promise<bool>>();
auto result_future = controller_action_client_->async_get_result(
current_goal_, [this, &result_callback_done](const auto& wrapped_result) {
current_goal_, [this, result_callback_done](const auto& wrapped_result) {
controllerDoneCallback(wrapped_result);
result_callback_done.set_value(true);
result_callback_done->set_value(true);
});
if (timeout.seconds() == 0.0)
if (timeout < std::chrono::nanoseconds(0))
{
result_future.wait();
}
Expand All @@ -161,7 +161,7 @@ class ActionBasedControllerHandle : public ActionBasedControllerHandleBase
}
}
// To accommodate for the delay after the future for the result is ready and the time controllerDoneCallback takes to finish
result_callback_done.get_future().wait();
result_callback_done->get_future().wait();
return true;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,12 +124,12 @@ void TfPublisher::publishPlanningSceneFrames()

void TfPublisher::initialize()
{
rclcpp::Node::SharedPtr n(new rclcpp::Node("TFPublisher"));
std::string prefix = context_->node_->get_name();
context_->node_->get_parameter_or("planning_scene_frame_publishing_rate", rate_, 10);
context_->node_->get_parameter_or("planning_scene_tf_prefix", prefix_, prefix);
if (!prefix_.empty())
prefix_ += "/";

std::string prefix = n->get_namespace();
prefix += "/";
n->get_parameter_or("planning_scene_frame_publishing_rate", rate_, 10);
n->get_parameter_or("planning_scene_tf_prefix", prefix_, prefix);
keep_running_ = true;

RCLCPP_INFO(LOGGER, "Initializing MoveGroupTfPublisher with a frame publishing rate of %d", rate_);
Expand Down