Skip to content

Commit b90c23a

Browse files
committed
Revert "Merge pull request moveit#724 from ros-planning/fixup-#716"
This reverts commit a8afa06, reversing changes made to 27e953e.
1 parent b60f26e commit b90c23a

File tree

6 files changed

+17
-19
lines changed

6 files changed

+17
-19
lines changed

move_group/src/default_capabilities/move_action_capability.cpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,6 @@ void move_group::MoveGroupMoveAction::initialize()
6161
void move_group::MoveGroupMoveAction::executeMoveCallback(const moveit_msgs::MoveGroupGoalConstPtr& goal)
6262
{
6363
setMoveState(PLANNING);
64-
context_->planning_scene_monitor_->updateFrameTransforms();
6564

6665
moveit_msgs::MoveGroupResult action_res;
6766
if (goal->planning_options.plan_only || !context_->allow_trajectory_execution_)
@@ -171,7 +170,6 @@ bool move_group::MoveGroupMoveAction::planUsingPlanningPipeline(const planning_i
171170
{
172171
setMoveState(PLANNING);
173172

174-
planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor_);
175173
bool solved = false;
176174
planning_interface::MotionPlanResponse res;
177175
try

move_group/src/default_capabilities/plan_service_capability.cpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,6 @@ bool move_group::MoveGroupPlanService::computePlanService(moveit_msgs::GetMotion
5252
{
5353
ROS_INFO("Received new planning service request...");
5454
context_->planning_scene_monitor_->syncSceneUpdates();
55-
context_->planning_scene_monitor_->updateFrameTransforms();
5655

5756
bool solved = false;
5857
planning_scene_monitor::LockedPlanningSceneRO ps(context_->planning_scene_monitor_);

planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -521,6 +521,7 @@ class PlanningSceneMonitor : private boost::noncopyable
521521
ros::CallbackQueue callback_queue_;
522522
boost::scoped_ptr<ros::AsyncSpinner> spinner_;
523523
ros::Time last_robot_motion_time_; /// Last time the robot has moved
524+
bool enforce_next_state_update_;
524525
};
525526

526527
typedef boost::shared_ptr<PlanningSceneMonitor> PlanningSceneMonitorPtr;

planning/planning_scene_monitor/src/planning_scene_monitor.cpp

Lines changed: 11 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -232,6 +232,7 @@ void planning_scene_monitor::PlanningSceneMonitor::initialize(const planning_sce
232232
shape_transform_cache_lookup_wait_time_ = ros::Duration(temp_wait_time);
233233

234234
state_update_pending_ = false;
235+
enforce_next_state_update_ = false;
235236
state_update_timer_ = nh_.createWallTimer(dt_state_update_,
236237
&PlanningSceneMonitor::stateUpdateTimerCallback,
237238
this,
@@ -823,6 +824,8 @@ void planning_scene_monitor::PlanningSceneMonitor::syncSceneUpdates(const ros::T
823824
if (t.isZero())
824825
return;
825826

827+
enforce_next_state_update_ = true; // enforce next state update to trigger without throttling
828+
826829
// Robot state updates in the scene are only triggered by the state monitor on changes of the state.
827830
// Hence, last_state_update_time_ might be much older than current_state_monitor_ (when robot didn't moved for a while).
828831
boost::shared_lock<boost::shared_mutex> lock(scene_update_mutex_);
@@ -831,21 +834,15 @@ void planning_scene_monitor::PlanningSceneMonitor::syncSceneUpdates(const ros::T
831834
last_robot_update < t && // wait for recent state update
832835
(t - last_robot_motion_time_).toSec() < 1.0) // but only if robot moved in last second
833836
{
834-
new_scene_update_condition_.wait_for(lock, boost::chrono::milliseconds(100));
837+
new_scene_update_condition_.wait_for(lock, boost::chrono::milliseconds(50));
835838
last_robot_update = current_state_monitor_->getCurrentStateTime();
836839
}
837-
// If there was a state monitor connected (and robot moved), the robot state should be up-to-date now
838-
// and last_update_time_ = last_robot_motion_time_
839-
840-
// If last scene update is recent and there are no pending updates, we are done.
841-
if (last_update_time_ >= t && callback_queue_.empty())
842-
return;
840+
// Now, we know that robot state is up-to-date
843841

844-
// Processing pending updates and wait for new incoming updates up to 1s.
845-
// This is necessary as publishing planning scene diffs is throttled (2Hz by default).
846-
while (!callback_queue_.empty() || (ros::Time::now()-t).toSec() < 1.)
842+
// ensure that last update time is more recent than t (or no more update events pending)
843+
while (last_update_time_ < t && !callback_queue_.empty())
847844
{
848-
new_scene_update_condition_.wait_for(lock, boost::chrono::seconds(1));
845+
new_scene_update_condition_.wait_for(lock, boost::chrono::milliseconds(50));
849846
}
850847
}
851848

@@ -1061,11 +1058,11 @@ void planning_scene_monitor::PlanningSceneMonitor::onStateUpdate(const sensor_ms
10611058
const ros::WallTime &n = ros::WallTime::now();
10621059
ros::WallDuration dt = n - wall_last_state_update_;
10631060

1064-
bool update = false;
1061+
bool update = enforce_next_state_update_;
10651062
{
10661063
boost::mutex::scoped_lock lock(state_pending_mutex_);
10671064

1068-
if (dt < dt_state_update_)
1065+
if (dt < dt_state_update_ && !update)
10691066
{
10701067
state_update_pending_ = true;
10711068
}
@@ -1171,6 +1168,7 @@ void planning_scene_monitor::PlanningSceneMonitor::updateSceneWithCurrentState()
11711168
boost::unique_lock<boost::shared_mutex> ulock(scene_update_mutex_);
11721169
last_update_time_ = last_robot_motion_time_ = current_state_monitor_->getCurrentStateTime();
11731170
current_state_monitor_->setToCurrentState(scene_->getCurrentStateNonConst());
1171+
enforce_next_state_update_ = false;
11741172
scene_->getCurrentStateNonConst().update(); // compute all transforms
11751173
}
11761174
triggerSceneUpdateEvent(UPDATE_STATE);

planning_interface/move_group_interface/src/move_group.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -709,7 +709,7 @@ class MoveGroup::MoveGroupImpl
709709
return false;
710710
}
711711
// TODO: check multi-DoF joints
712-
if (fabs(current_state->getJointPositions(jm)[0] - positions[i]) > std::numeric_limits<float>::epsilon())
712+
if (fabs(current_state->getJointPositions(jm)[0] - positions[i]) < std::numeric_limits<float>::epsilon())
713713
{
714714
ROS_ERROR("Trajectory start deviates from current robot state");
715715
return false;

visualization/motion_planning_rviz_plugin/src/motion_planning_frame_planning.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -406,10 +406,11 @@ void MotionPlanningFrame::remoteUpdateStartStateCallback(const std_msgs::EmptyCo
406406
if (move_group_ && planning_display_)
407407
{
408408
planning_display_->syncSceneUpdates();
409+
robot_state::RobotState state = *planning_display_->getQueryStartState();
409410
const planning_scene_monitor::LockedPlanningSceneRO &ps = planning_display_->getPlanningSceneRO();
410411
if (ps)
411412
{
412-
robot_state::RobotState state = ps->getCurrentState();
413+
state = ps->getCurrentState();
413414
planning_display_->setQueryStartState(state);
414415
}
415416
}
@@ -420,10 +421,11 @@ void MotionPlanningFrame::remoteUpdateGoalStateCallback(const std_msgs::EmptyCon
420421
if (move_group_ && planning_display_)
421422
{
422423
planning_display_->syncSceneUpdates();
424+
robot_state::RobotState state = *planning_display_->getQueryStartState();
423425
const planning_scene_monitor::LockedPlanningSceneRO &ps = planning_display_->getPlanningSceneRO();
424426
if (ps)
425427
{
426-
robot_state::RobotState state = ps->getCurrentState();
428+
state = ps->getCurrentState();
427429
planning_display_->setQueryGoalState(state);
428430
}
429431
}

0 commit comments

Comments
 (0)