Apply clang-format-10 (#199)

This commit is contained in:
Michael Görner 2020-08-20 11:56:53 +02:00 committed by GitHub
parent 47f052b93d
commit ee6c50ad31
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
37 changed files with 97 additions and 91 deletions

View File

@ -24,6 +24,7 @@ BraceWrapping:
BeforeCatch: false BeforeCatch: false
BeforeElse: false BeforeElse: false
IndentBraces: false IndentBraces: false
SplitEmptyRecord: false
BreakBeforeBinaryOperators: None BreakBeforeBinaryOperators: None
BreakBeforeBraces: Custom BreakBeforeBraces: Custom
BreakBeforeTernaryOperators: false BreakBeforeTernaryOperators: false

View File

@ -120,7 +120,7 @@ class ParallelContainerBase;
* - Fallbacks: the children are considered in series * - Fallbacks: the children are considered in series
* - Merger: solutions of all children (actuating disjoint groups) * - Merger: solutions of all children (actuating disjoint groups)
* are merged into a single solution for parallel execution * are merged into a single solution for parallel execution
*/ */
class ParallelContainerBase : public ContainerBase class ParallelContainerBase : public ContainerBase
{ {
public: public:

View File

@ -49,8 +49,8 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup)
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} } // namespace core
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -12,8 +12,8 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
MOVEIT_CLASS_FORWARD(LinkModel) MOVEIT_CLASS_FORWARD(LinkModel)
} } // namespace core
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -54,8 +54,8 @@ namespace core {
MOVEIT_CLASS_FORWARD(LinkModel) MOVEIT_CLASS_FORWARD(LinkModel)
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup)
} } // namespace core
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -54,7 +54,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
} }
} } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene)

View File

@ -45,8 +45,8 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup)
} } // namespace core
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -47,7 +47,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -48,7 +48,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(JointModelGroup) MOVEIT_CLASS_FORWARD(JointModelGroup)
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -48,7 +48,7 @@ namespace moveit {
namespace core { namespace core {
class RobotState; class RobotState;
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace stages { namespace stages {

View File

@ -48,7 +48,7 @@ namespace moveit {
namespace core { namespace core {
class RobotState; class RobotState;
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace stages { namespace stages {
@ -101,10 +101,10 @@ protected:
bool getJointStateGoal(const boost::any& goal, const core::JointModelGroup* jmg, moveit::core::RobotState& state); bool getJointStateGoal(const boost::any& goal, const core::JointModelGroup* jmg, moveit::core::RobotState& state);
bool getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg, bool getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg,
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
decltype(std::declval<SolutionBase>().markers()) & markers); decltype(std::declval<SolutionBase>().markers())& markers);
bool getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link, bool getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link,
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
decltype(std::declval<SolutionBase>().markers()) & /*unused*/); decltype(std::declval<SolutionBase>().markers())& /*unused*/);
protected: protected:
solvers::PlannerInterfacePtr planner_; solvers::PlannerInterfacePtr planner_;

View File

@ -41,7 +41,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {

View File

@ -45,7 +45,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
} }
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
namespace stages { namespace stages {

View File

@ -182,10 +182,10 @@ private:
// restrict access to some functions to ensure consistency // restrict access to some functions to ensure consistency
// (we need to set/unset InterfaceState::owner_) // (we need to set/unset InterfaceState::owner_)
using base_type::moveTo;
using base_type::moveFrom;
using base_type::insert;
using base_type::erase; using base_type::erase;
using base_type::insert;
using base_type::moveFrom;
using base_type::moveTo;
using base_type::remove_if; using base_type::remove_if;
}; };
@ -329,4 +329,4 @@ struct less<moveit::task_constructor::SolutionBase*>
return *x < *y; return *x < *y;
} }
}; };
} } // namespace std

View File

@ -52,8 +52,8 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} } // namespace core
} } // namespace moveit
namespace moveit { namespace moveit {
namespace task_constructor { namespace task_constructor {
@ -108,9 +108,9 @@ public:
void eraseTaskCallback(TaskCallbackList::const_iterator which); void eraseTaskCallback(TaskCallbackList::const_iterator which);
/// expose SolutionCallback API /// expose SolutionCallback API
using WrapperBase::SolutionCallback;
using WrapperBase::addSolutionCallback; using WrapperBase::addSolutionCallback;
using WrapperBase::removeSolutionCallback; using WrapperBase::removeSolutionCallback;
using WrapperBase::SolutionCallback;
/// reset all stages /// reset all stages
void reset() final; void reset() final;

View File

@ -54,7 +54,8 @@ struct is_container_helper
template <typename T> template <typename T>
struct is_container< struct is_container<
T, std::conditional_t<false, is_container_helper<typename T::const_iterator, decltype(std::declval<T>().cbegin()), T, std::conditional_t<false,
is_container_helper<typename T::const_iterator, decltype(std::declval<T>().cbegin()),
decltype(std::declval<T>().cend())>, decltype(std::declval<T>().cend())>,
void> > : public std::true_type void> > : public std::true_type
{}; {};

View File

@ -57,7 +57,7 @@ std::string getProcessId() {
gethostname(our_hostname, sizeof(our_hostname) - 1); gethostname(our_hostname, sizeof(our_hostname) - 1);
return std::to_string(getpid()) + "@" + our_hostname; return std::to_string(getpid()) + "@" + our_hostname;
} }
} } // namespace
class IntrospectionPrivate class IntrospectionPrivate
{ {

View File

@ -47,6 +47,6 @@ PlannerInterface::PlannerInterface() {
p.declare<double>("max_velocity_scaling_factor", 1.0, "scale down max velocity by this factor"); p.declare<double>("max_velocity_scaling_factor", 1.0, "scale down max velocity by this factor");
p.declare<double>("max_acceleration_scaling_factor", 1.0, "scale down max acceleration by this factor"); p.declare<double>("max_acceleration_scaling_factor", 1.0, "scale down max acceleration by this factor");
} }
} } // namespace solvers
} } // namespace task_constructor
} // namespace moveit } // namespace moveit

View File

@ -354,8 +354,9 @@ void ComputeIK::compute() {
double min_solution_distance = props.get<double>("min_solution_distance"); double min_solution_distance = props.get<double>("min_solution_distance");
IKSolutions ik_solutions; IKSolutions ik_solutions;
auto is_valid = [sandbox_scene, ignore_collisions, min_solution_distance, &ik_solutions]( auto is_valid = [sandbox_scene, ignore_collisions, min_solution_distance,
robot_state::RobotState* state, const robot_model::JointModelGroup* jmg, const double* joint_positions) { &ik_solutions](robot_state::RobotState* state, const robot_model::JointModelGroup* jmg,
const double* joint_positions) {
for (const auto& sol : ik_solutions) { for (const auto& sol : ik_solutions) {
if (jmg->distance(joint_positions, sol.data()) < min_solution_distance) if (jmg->distance(joint_positions, sol.data()) < min_solution_distance)
return false; // too close to already found solution return false; // too close to already found solution

View File

@ -72,8 +72,8 @@ bool computeCorrection(const std::vector<cd::Contact>& contacts, Eigen::Vector3d
correction.setZero(); correction.setZero();
for (const cd::Contact& c : contacts) { for (const cd::Contact& c : contacts) {
if ((c.body_type_1 != cd::BodyTypes::WORLD_OBJECT && c.body_type_2 != cd::BodyTypes::WORLD_OBJECT)) { if ((c.body_type_1 != cd::BodyTypes::WORLD_OBJECT && c.body_type_2 != cd::BodyTypes::WORLD_OBJECT)) {
ROS_WARN_STREAM_NAMED("FixCollisionObjects", "Cannot fix collision between " << c.body_name_1 << " and " ROS_WARN_STREAM_NAMED("FixCollisionObjects",
<< c.body_name_2); "Cannot fix collision between " << c.body_name_1 << " and " << c.body_name_2);
return false; return false;
} }
if (c.body_type_1 == cd::BodyTypes::WORLD_OBJECT) if (c.body_type_1 == cd::BodyTypes::WORLD_OBJECT)

View File

@ -125,7 +125,7 @@ bool MoveTo::getJointStateGoal(const boost::any& goal, const moveit::core::Joint
bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg, bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStamped& ik_pose_msg,
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
decltype(std::declval<SolutionBase>().markers()) & markers) { decltype(std::declval<SolutionBase>().markers())& markers) {
try { try {
const geometry_msgs::PoseStamped& target = boost::any_cast<geometry_msgs::PoseStamped>(goal); const geometry_msgs::PoseStamped& target = boost::any_cast<geometry_msgs::PoseStamped>(goal);
tf::poseMsgToEigen(target.pose, target_eigen); tf::poseMsgToEigen(target.pose, target_eigen);
@ -147,7 +147,7 @@ bool MoveTo::getPoseGoal(const boost::any& goal, const geometry_msgs::PoseStampe
bool MoveTo::getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link, bool MoveTo::getPointGoal(const boost::any& goal, const moveit::core::LinkModel* link,
const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen, const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen,
decltype(std::declval<SolutionBase>().markers()) & /*unused*/) { decltype(std::declval<SolutionBase>().markers())& /*unused*/) {
try { try {
const geometry_msgs::PointStamped& target = boost::any_cast<geometry_msgs::PointStamped>(goal); const geometry_msgs::PointStamped& target = boost::any_cast<geometry_msgs::PointStamped>(goal);
Eigen::Vector3d target_point; Eigen::Vector3d target_point;

View File

@ -6,7 +6,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
} }
} } // namespace moveit
// get a hard-coded model // get a hard-coded model
moveit::core::RobotModelPtr getModel(); moveit::core::RobotModelPtr getModel();

View File

@ -48,7 +48,7 @@ namespace rviz {
class Property; class Property;
class PropertyTreeModel; class PropertyTreeModel;
class DisplayContext; class DisplayContext;
} } // namespace rviz
namespace planning_scene { namespace planning_scene {
class PlanningScene; class PlanningScene;
} }
@ -56,7 +56,7 @@ namespace moveit {
namespace task_constructor { namespace task_constructor {
class Stage; class Stage;
} }
} } // namespace moveit
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {

View File

@ -11,5 +11,5 @@ const Icon FORWARD({ { QLatin1String(":icons/downarrow.png"), QColor::fromRgba(0
const Icon BACKWARD({ { QLatin1String(":icons/uparrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT); const Icon BACKWARD({ { QLatin1String(":icons/uparrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
const Icon BOTHWAY({ { QLatin1String(":icons/updownarrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT); const Icon BOTHWAY({ { QLatin1String(":icons/updownarrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
const Icon GENERATE({ { QLatin1String(":icons/generatearrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT); const Icon GENERATE({ { QLatin1String(":icons/generatearrow.png"), QColor::fromRgba(0xff000000) } }, Icon::TINT);
} } // namespace icons
} } // namespace moveit_rviz_plugin

View File

@ -10,5 +10,5 @@ extern const moveit_rviz_plugin::utils::Icon FORWARD;
extern const moveit_rviz_plugin::utils::Icon BACKWARD; extern const moveit_rviz_plugin::utils::Icon BACKWARD;
extern const moveit_rviz_plugin::utils::Icon BOTHWAY; extern const moveit_rviz_plugin::utils::Icon BOTHWAY;
extern const moveit_rviz_plugin::utils::Icon GENERATE; extern const moveit_rviz_plugin::utils::Icon GENERATE;
} } // namespace icons
} } // namespace moveit_rviz_plugin

View File

@ -54,13 +54,13 @@
namespace rviz { namespace rviz {
class StringProperty; class StringProperty;
class RosTopicProperty; class RosTopicProperty;
} } // namespace rviz
namespace moveit { namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
} }
} } // namespace moveit
namespace rdf_loader { namespace rdf_loader {
MOVEIT_CLASS_FORWARD(RDFLoader) MOVEIT_CLASS_FORWARD(RDFLoader)
} }

View File

@ -58,7 +58,7 @@ class ServiceClient;
namespace rviz { namespace rviz {
class PropertyTreeModel; class PropertyTreeModel;
class DisplayContext; class DisplayContext;
} } // namespace rviz
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {

View File

@ -49,7 +49,7 @@ class WindowManagerInterface;
class Property; class Property;
class BoolProperty; class BoolProperty;
class EnumProperty; class EnumProperty;
} } // namespace rviz
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {
@ -108,7 +108,7 @@ class MetaTaskListModel;
* Subscribing to task_monitoring and task_solution topics, it collects information * Subscribing to task_monitoring and task_solution topics, it collects information
* about running tasks and their solutions and allows to inspect both, * about running tasks and their solutions and allows to inspect both,
* successful solutions and failed solution attempts. * successful solutions and failed solution attempts.
*/ */
class TaskViewPrivate; class TaskViewPrivate;
class TaskView : public SubPanel class TaskView : public SubPanel
{ {

View File

@ -61,8 +61,9 @@ void modifySourceModel(QAbstractItemModel* src, T* proxy, const QModelIndex& src
const char* new_value = "foo"; const char* new_value = "foo";
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
auto con = proxy->connect(proxy, &T::dataChanged, [&called, &src_index, new_value](const QModelIndex& topLeft, auto con =
const QModelIndex& bottomRight) { proxy->connect(proxy, &T::dataChanged,
[&called, &src_index, new_value](const QModelIndex& topLeft, const QModelIndex& bottomRight) {
EXPECT_EQ(topLeft.row(), src_index.row()); EXPECT_EQ(topLeft.row(), src_index.row());
EXPECT_EQ(topLeft.column(), src_index.column()); EXPECT_EQ(topLeft.column(), src_index.column());

View File

@ -43,7 +43,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} }
} } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene)
} }

View File

@ -14,7 +14,7 @@ class SceneNode;
namespace rviz { namespace rviz {
class DisplayContext; class DisplayContext;
class MarkerBase; class MarkerBase;
} } // namespace rviz
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene)
@ -23,7 +23,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotState) MOVEIT_CLASS_FORWARD(RobotState)
} }
} } // namespace moveit
namespace moveit_rviz_plugin { namespace moveit_rviz_plugin {

View File

@ -67,7 +67,7 @@ namespace moveit {
namespace core { namespace core {
MOVEIT_CLASS_FORWARD(RobotModel) MOVEIT_CLASS_FORWARD(RobotModel)
} }
} } // namespace moveit
namespace planning_scene { namespace planning_scene {
MOVEIT_CLASS_FORWARD(PlanningScene) MOVEIT_CLASS_FORWARD(PlanningScene)
} }

View File

@ -72,8 +72,8 @@ namespace moveit_rviz_plugin {
TaskSolutionVisualization::TaskSolutionVisualization(rviz::Property* parent, rviz::Display* display) TaskSolutionVisualization::TaskSolutionVisualization(rviz::Property* parent, rviz::Display* display)
: display_(display) { : display_(display) {
// trajectory properties // trajectory properties
interrupt_display_property_ = interrupt_display_property_ = new rviz::BoolProperty("Interrupt Display", false,
new rviz::BoolProperty("Interrupt Display", false, "Immediately show newly planned trajectory, " "Immediately show newly planned trajectory, "
"interrupting the currently displayed one.", "interrupting the currently displayed one.",
parent); parent);
@ -84,8 +84,9 @@ TaskSolutionVisualization::TaskSolutionVisualization(rviz::Property* parent, rvi
trail_display_property_ = trail_display_property_ =
new rviz::BoolProperty("Show Trail", false, "Show a path trail", parent, SLOT(changedTrail()), this); new rviz::BoolProperty("Show Trail", false, "Show a path trail", parent, SLOT(changedTrail()), this);
state_display_time_property_ = new rviz::EditableEnumProperty( state_display_time_property_ =
"State Display Time", "0.05 s", "The amount of wall-time to wait in between displaying " new rviz::EditableEnumProperty("State Display Time", "0.05 s",
"The amount of wall-time to wait in between displaying "
"states along a received trajectory path", "states along a received trajectory path",
parent); parent);
state_display_time_property_->addOptionStd("REALTIME"); state_display_time_property_->addOptionStd("REALTIME");
@ -100,13 +101,14 @@ TaskSolutionVisualization::TaskSolutionVisualization(rviz::Property* parent, rvi
// robot properties // robot properties
robot_property_ = new rviz::Property("Robot", QString(), QString(), parent); robot_property_ = new rviz::Property("Robot", QString(), QString(), parent);
robot_visual_enabled_property_ = robot_visual_enabled_property_ = new rviz::BoolProperty("Show Robot Visual", true,
new rviz::BoolProperty("Show Robot Visual", true, "Indicates whether the geometry of the robot as defined for " "Indicates whether the geometry of the robot as defined for "
"visualisation purposes should be displayed", "visualisation purposes should be displayed",
robot_property_, SLOT(changedRobotVisualEnabled()), this); robot_property_, SLOT(changedRobotVisualEnabled()), this);
robot_collision_enabled_property_ = robot_collision_enabled_property_ =
new rviz::BoolProperty("Show Robot Collision", false, "Indicates whether the geometry of the robot as defined " new rviz::BoolProperty("Show Robot Collision", false,
"Indicates whether the geometry of the robot as defined "
"for collision detection purposes should be displayed", "for collision detection purposes should be displayed",
robot_property_, SLOT(changedRobotCollisionEnabled()), this); robot_property_, SLOT(changedRobotCollisionEnabled()), this);
@ -119,8 +121,8 @@ TaskSolutionVisualization::TaskSolutionVisualization(rviz::Property* parent, rvi
new rviz::ColorProperty("Fixed Robot Color", QColor(150, 50, 150), "The color of the animated robot", new rviz::ColorProperty("Fixed Robot Color", QColor(150, 50, 150), "The color of the animated robot",
robot_property_, SLOT(changedRobotColor()), this); robot_property_, SLOT(changedRobotColor()), this);
enable_robot_color_property_ = enable_robot_color_property_ = new rviz::BoolProperty("Use Fixed Robot Color", false,
new rviz::BoolProperty("Use Fixed Robot Color", false, "Specifies whether the fixed robot color should be used." "Specifies whether the fixed robot color should be used."
" If not, the original color is used.", " If not, the original color is used.",
robot_property_, SLOT(enabledRobotColor()), this); robot_property_, SLOT(enabledRobotColor()), this);
@ -404,9 +406,8 @@ void TaskSolutionVisualization::update(float wall_dt, float ros_dt) {
current_state_time_ = 0.0; current_state_time_ = 0.0;
trail_scene_node_->setVisible(false); trail_scene_node_->setVisible(false);
} else if (tm < 0.0) { // using realtime: skip to next waypoint based on elapsed display time } else if (tm < 0.0) { // using realtime: skip to next waypoint based on elapsed display time
while (current_state_ < max_state_index && while (current_state_ < max_state_index && (tm = displaying_solution_->getWayPointDurationFromPrevious(
(tm = displaying_solution_->getWayPointDurationFromPrevious(current_state_ + 1)) < current_state_ + 1)) < current_state_time_) {
current_state_time_) {
++current_state_; ++current_state_;
current_state_time_ -= tm; current_state_time_ -= tm;
} }
@ -618,9 +619,10 @@ void TaskSolutionVisualization::setVisibility(Ogre::SceneNode* node, Ogre::Scene
void TaskSolutionVisualization::setVisibility() { void TaskSolutionVisualization::setVisibility() {
// main scene node is visible if animation, trail, or panel is shown, or if display is locked // main scene node is visible if animation, trail, or panel is shown, or if display is locked
setVisibility(main_scene_node_, parent_scene_node_, display_->isEnabled() && displaying_solution_ && setVisibility(
(animating_ || locked_ || trail_scene_node_->getParent() || main_scene_node_, parent_scene_node_,
(slider_panel_ && slider_panel_->isVisible()))); display_->isEnabled() && displaying_solution_ &&
(animating_ || locked_ || trail_scene_node_->getParent() || (slider_panel_ && slider_panel_->isVisible())));
} }
} // namespace moveit_rviz_plugin } // namespace moveit_rviz_plugin