From 97edff950f389cc9c7880ed2e7ba4b3a652e3539 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Fri, 12 Jul 2019 16:38:45 +0200 Subject: [PATCH 01/96] fix World::getTransform (#1553) ... which was broken in 3e8feeb637 (#1439) --- moveit_core/collision_detection/src/world.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/moveit_core/collision_detection/src/world.cpp b/moveit_core/collision_detection/src/world.cpp index 4fbf16e76c..f2a404ec8f 100644 --- a/moveit_core/collision_detection/src/world.cpp +++ b/moveit_core/collision_detection/src/world.cpp @@ -168,6 +168,7 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name) const const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& frame_found) const { + frame_found = true; std::map::const_iterator it = objects_.find(name); if (it != objects_.end()) return it->second->shape_poses_[0]; @@ -180,10 +181,7 @@ const Eigen::Isometry3d& World::getTransform(const std::string& name, bool& fram { auto it = object.second->subframe_poses_.find(name.substr(object.first.length() + 1)); if (it != object.second->subframe_poses_.end()) - { - frame_found = true; return it->second; - } } } } From 56b7c61a88287bf027415d96ce038de668d2e05a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Fri, 12 Jul 2019 21:18:20 +0200 Subject: [PATCH 02/96] add RobotTrajectory::getDuration() (#1554) --- .../include/moveit/robot_trajectory/robot_trajectory.h | 2 ++ moveit_core/robot_trajectory/src/robot_trajectory.cpp | 8 ++++++-- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index 64f4fe309e..7b3a4b9507 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -202,6 +202,8 @@ class RobotTrajectory void clear(); + double getDuration() const; + double getAverageSegmentDuration() const; void getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory& trajectory) const; diff --git a/moveit_core/robot_trajectory/src/robot_trajectory.cpp b/moveit_core/robot_trajectory/src/robot_trajectory.cpp index b0d5de749f..0c96f9c8dd 100644 --- a/moveit_core/robot_trajectory/src/robot_trajectory.cpp +++ b/moveit_core/robot_trajectory/src/robot_trajectory.cpp @@ -66,13 +66,17 @@ const std::string& RobotTrajectory::getGroupName() const return EMPTY; } +double RobotTrajectory::getDuration() const +{ + return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0); +} + double RobotTrajectory::getAverageSegmentDuration() const { if (duration_from_previous_.empty()) return 0.0; else - return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0) / - (double)duration_from_previous_.size(); + return getDuration() / static_cast(duration_from_previous_.size()); } void RobotTrajectory::swap(RobotTrajectory& other) From b853c6bc48c41af7475db8cbb4d11078bb8725eb Mon Sep 17 00:00:00 2001 From: Bianca Homberg Date: Tue, 16 Jul 2019 03:05:06 -0700 Subject: [PATCH 03/96] Ensure that if time parameterization fails, error is appropriately propogated (#1562) --- .../src/add_iterative_spline_parameterization.cpp | 5 ++++- .../src/add_time_optimal_parameterization.cpp | 5 ++++- .../src/add_time_parameterization.cpp | 5 ++++- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/add_iterative_spline_parameterization.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/add_iterative_spline_parameterization.cpp index 6904160457..bf4f89a2b8 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/add_iterative_spline_parameterization.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/add_iterative_spline_parameterization.cpp @@ -68,7 +68,10 @@ class AddIterativeSplineParameterization : public planning_request_adapter::Plan ROS_DEBUG("Running '%s'", getDescription().c_str()); if (!time_param_.computeTimeStamps(*res.trajectory_, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor)) - ROS_WARN("Time parametrization for the solution path failed."); + { + ROS_ERROR("Time parametrization for the solution path failed."); + result = false; + } } return result; diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_optimal_parameterization.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_optimal_parameterization.cpp index 805e6b7329..336307fedb 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_optimal_parameterization.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_optimal_parameterization.cpp @@ -71,7 +71,10 @@ class AddTimeOptimalParameterization : public planning_request_adapter::Planning TimeOptimalTrajectoryGeneration totg; if (!totg.computeTimeStamps(*res.trajectory_, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor)) - ROS_WARN("Time parametrization for the solution path failed."); + { + ROS_ERROR("Time parametrization for the solution path failed."); + result = false; + } } return result; diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_parameterization.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_parameterization.cpp index be06624689..e3d1b17522 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_parameterization.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/add_time_parameterization.cpp @@ -67,7 +67,10 @@ class AddTimeParameterization : public planning_request_adapter::PlanningRequest ROS_DEBUG("Running '%s'", getDescription().c_str()); if (!time_param_.computeTimeStamps(*res.trajectory_, req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor)) - ROS_WARN("Time parametrization for the solution path failed."); + { + ROS_ERROR("Time parametrization for the solution path failed."); + result = false; + } } return result; From 6c7e84c4c5185cf86c4b1daa1bdf898fd9a1e3fc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Fri, 19 Jul 2019 12:10:27 +0200 Subject: [PATCH 04/96] Use portable string() on filesystem::path. (#1571) --- .../src/tools/moveit_config_data.cpp | 2 +- .../widgets/configuration_files_widget.cpp | 4 ++-- .../src/widgets/start_screen_widget.cpp | 20 +++++++++---------- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index b563b7e882..124246f6c1 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -1693,7 +1693,7 @@ std::string MoveItConfigData::appendPaths(const std::string& path1, const std::s { fs::path result = path1; result /= path2; - return result.make_preferred().native(); + return result.make_preferred().string(); } srdf::Model::Group* MoveItConfigData::findGroupByName(const std::string& name) diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index 1f87a5a506..4b1097d974 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -183,7 +183,7 @@ bool ConfigurationFilesWidget::loadGenFiles() fs::path template_package_path = config_data_->setup_assistant_path_; template_package_path /= "templates"; template_package_path /= "moveit_config_pkg_template"; - config_data_->template_package_path_ = template_package_path.make_preferred().native(); + config_data_->template_package_path_ = template_package_path.make_preferred().string(); if (!fs::is_directory(config_data_->template_package_path_)) { @@ -1008,7 +1008,7 @@ const std::string ConfigurationFilesWidget::getPackageName(std::string package_p std::string package_name; fs::path fs_package_path = package_path; - package_name = fs_package_path.filename().c_str(); + package_name = fs_package_path.filename().string(); // check for empty if (package_name.empty()) diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index 8a8fadbd27..fe54c91fa2 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -400,14 +400,14 @@ bool StartScreenWidget::loadExistingFiles() fs::path kinematics_yaml_path = config_data_->config_pkg_path_; kinematics_yaml_path /= "config/kinematics.yaml"; - if (!config_data_->inputKinematicsYAML(kinematics_yaml_path.make_preferred().native())) + if (!config_data_->inputKinematicsYAML(kinematics_yaml_path.make_preferred().string())) { QMessageBox::warning(this, "No Kinematic YAML File", QString("Failed to parse kinematics yaml file. This file is not critical but any previous " "kinematic solver settings have been lost. To re-populate this file edit each " "existing planning group and choose a solver, then save each change. \n\nFile error " "at location ") - .append(kinematics_yaml_path.make_preferred().native().c_str())); + .append(kinematics_yaml_path.make_preferred().string().c_str())); } // Load 3d_sensors config file @@ -416,11 +416,11 @@ bool StartScreenWidget::loadExistingFiles() // Load ros controllers yaml file if available----------------------------------------------- fs::path ros_controllers_yaml_path = config_data_->config_pkg_path_; ros_controllers_yaml_path /= "config/ros_controllers.yaml"; - config_data_->inputROSControllersYAML(ros_controllers_yaml_path.make_preferred().native()); + config_data_->inputROSControllersYAML(ros_controllers_yaml_path.make_preferred().string()); fs::path ompl_yaml_path = config_data_->config_pkg_path_; ompl_yaml_path /= "config/ompl_planning.yaml"; - config_data_->inputOMPLYAML(ompl_yaml_path.make_preferred().native()); + config_data_->inputOMPLYAML(ompl_yaml_path.make_preferred().string()); // DONE LOADING -------------------------------------------------------------------------- @@ -645,7 +645,7 @@ bool StartScreenWidget::extractPackageNameFromPath() // Copy path into vector of parts for (fs::path::iterator it = urdf_directory.begin(); it != urdf_directory.end(); ++it) - path_parts.push_back(it->native()); + path_parts.push_back(it->string()); bool package_found = false; @@ -670,7 +670,7 @@ bool StartScreenWidget::extractPackageNameFromPath() // check if this directory has a package.xml package_path = sub_path; package_path /= "package.xml"; - ROS_DEBUG_STREAM("Checking for " << package_path.make_preferred().native()); + ROS_DEBUG_STREAM("Checking for " << package_path.make_preferred().string()); // Check if the files exist if (fs::is_regular_file(package_path) || fs::is_regular_file(sub_path / "manifest.xml")) @@ -711,7 +711,7 @@ bool StartScreenWidget::extractPackageNameFromPath() // Success config_data_->urdf_pkg_name_ = package_name; - config_data_->urdf_pkg_relative_path_ = relative_path.make_preferred().native(); + config_data_->urdf_pkg_relative_path_ = relative_path.make_preferred().string(); } ROS_DEBUG_STREAM("URDF Package Name: " << config_data_->urdf_pkg_name_); @@ -781,12 +781,12 @@ bool StartScreenWidget::load3DSensorsFile() if (!fs::is_regular_file(sensors_3d_yaml_path)) { - return config_data_->input3DSensorsYAML(default_sensors_3d_yaml_path.make_preferred().native()); + return config_data_->input3DSensorsYAML(default_sensors_3d_yaml_path.make_preferred().string()); } else { - return config_data_->input3DSensorsYAML(default_sensors_3d_yaml_path.make_preferred().native(), - sensors_3d_yaml_path.make_preferred().native()); + return config_data_->input3DSensorsYAML(default_sensors_3d_yaml_path.make_preferred().string(), + sensors_3d_yaml_path.make_preferred().string()); } } From fd0a52ebcc04accd1a9e0ef73fc7314ebbd3fc27 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Thu, 25 Jul 2019 08:56:02 -0600 Subject: [PATCH 05/96] MoveIt benchmark improvements (#1510) * Add pseudo experiment all_experiments to allow comparing all entries * Expose loadBenchmarkQueryData() for setting up custom queries * Add benchmark entry for comparing the 'final' result trajectory Different planners don't always use the same description pattern in their MotionPlanDetailedResponse. This makes it difficult to compare benchmark results. This adds an extra field where all values of the last solution trajectory are stored. * Add trajectory similarity function to measure repeatability * Address requested changes * Fill empty fields in all_experiments * Improve variable and function names * Add helper function computeTrajectoryDistance() --- .../moveit/benchmarks/BenchmarkExecutor.h | 21 ++ .../scripts/moveit_benchmark_statistics.py | 51 ++++- .../benchmarks/src/BenchmarkExecutor.cpp | 209 +++++++++++++++--- 3 files changed, 238 insertions(+), 43 deletions(-) diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index ed88584133..b2aafebe90 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -141,9 +141,30 @@ class BenchmarkExecutor virtual bool initializeBenchmarks(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, std::vector& queries); + /// Initialize benchmark query data from start states and constraints + virtual bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, + std::vector& start_states, + std::vector& path_constraints, + std::vector& goal_constraints, + std::vector& traj_constraints, + std::vector& queries); + virtual void collectMetrics(PlannerRunData& metrics, const planning_interface::MotionPlanDetailedResponse& mp_res, bool solved, double total_time); + /// Compute the similarity of each (final) trajectory to all other (final) trajectories in the experiment and write + /// the results to planner_data metrics + void computeAveragePathSimilarities(PlannerBenchmarkData& planner_data, + const std::vector& responses, + const std::vector& solved); + + /// Helper function used by computeAveragePathSimilarities() for computing a heuristic distance metric between two + /// robot trajectories. This function aligns both trajectories in a greedy fashion and computes the mean waypoint + /// distance averaged over all aligned waypoints. Using a greedy approach is more efficient than dynamic time warping, + /// and seems to be sufficient for similar trajectories. + bool computeTrajectoryDistance(const robot_trajectory::RobotTrajectory& traj_first, + const robot_trajectory::RobotTrajectory& traj_second, double& result_distance); + virtual void writeOutput(const BenchmarkRequest& brequest, const std::string& start_time, double benchmark_duration); void shiftConstraintsByOffset(moveit_msgs::Constraints& constraints, const std::vector& offset); diff --git a/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py b/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py index fd84005a33..666e64c60d 100755 --- a/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py +++ b/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py @@ -112,7 +112,7 @@ def readBenchmarkLog(dbname, filenames): # create all tables if they don't already exist c.executescript("""CREATE TABLE IF NOT EXISTS experiments - (id INTEGER PRIMARY KEY AUTOINCREMENT, name VARCHAR(512), + (id INTEGER PRIMARY KEY ON CONFLICT REPLACE AUTOINCREMENT, name VARCHAR(512), totaltime REAL, timelimit REAL, memorylimit REAL, runcount INTEGER, version VARCHAR(128), hostname VARCHAR(1024), cpuinfo TEXT, date DATETIME, seed INTEGER, setup TEXT); @@ -130,7 +130,19 @@ def readBenchmarkLog(dbname, filenames): (runid INTEGER, time REAL, PRIMARY KEY (runid, time), FOREIGN KEY (runid) REFERENCES runs(id) ON DELETE CASCADE)""") - for filename in filenames: + # add placeholder entry for all_experiments + allExperimentsName = "all_experiments" + allExperimentsValues = { + "totaltime": 0.0, "timelimit": 0.0, "memorylimit": 0.0, "runcount": 0, "version": "0.0.0", + "hostname": "", "cpuinfo": "", "date": 0, "seed": 0, "setup": "" + } + addAllExperiments = len(filenames) > 0 + if addAllExperiments: + c.execute('INSERT INTO experiments VALUES (?,?,?,?,?,?,?,?,?,?,?,?)', + (None, allExperimentsName) + tuple(allExperimentsValues.values())) + allExperimentsId = c.lastrowid + + for i, filename in enumerate(filenames): print('Processing ' + filename) logfile = open(filename,'r') start_pos = logfile.tell() @@ -155,7 +167,19 @@ def readBenchmarkLog(dbname, filenames): nrruns = -1 if nrrunsOrNone != None: nrruns = int(nrrunsOrNone) + allExperimentsValues['runcount'] += nrruns totaltime = float(readRequiredLogValue("total time", logfile, 0, {-3 : "collect", -2 : "the", -1 : "data"})) + # fill in fields of all_experiments + allExperimentsValues['totaltime'] += totaltime + allExperimentsValues['memorylimit'] = max(allExperimentsValues['memorylimit'], totaltime) + allExperimentsValues['timelimit'] = max(allExperimentsValues['timelimit'], totaltime) + # copy the fields of the first file to all_experiments so that they are not empty + if (i==0): + allExperimentsValues['version'] = version + allExperimentsValues['date'] = date + allExperimentsValues['setup'] = expsetup + allExperimentsValues['hostname'] = hostname + allExperimentsValues['cpuinfo'] = cpuinfo numEnums = 0 numEnumsOrNone = readOptionalLogValue(logfile, 0, {-2 : "enum"}) if numEnumsOrNone != None: @@ -213,13 +237,17 @@ def readBenchmarkLog(dbname, filenames): numRuns = int(logfile.readline().split()[0]) runIds = [] for j in range(numRuns): - values = tuple([experimentId, plannerId] + \ - [None if len(x) == 0 or x == 'nan' or x == 'inf' else x - for x in logfile.readline().split('; ')[:-1]]) + runValues = [None if len(x) == 0 or x == 'nan' or x == 'inf' else x + for x in logfile.readline().split('; ')[:-1]] + values = tuple([experimentId, plannerId] + runValues) c.execute(insertFmtStr, values) # extract primary key of each run row so we can reference them # in the planner progress data table if needed runIds.append(c.lastrowid) + # add all run data to all_experiments + if addAllExperiments: + values = tuple([allExperimentsId, plannerId] + runValues) + c.execute(insertFmtStr, values) nextLine = logfile.readline().strip() @@ -259,6 +287,15 @@ def readBenchmarkLog(dbname, filenames): logfile.readline() logfile.close() + + if addAllExperiments: + updateString = "UPDATE experiments SET" + for i, (key, val) in enumerate(allExperimentsValues.items()): + if i > 0: + updateString += "," + updateString += " " + str(key) + "='" + str(val) + "'" + updateString += "WHERE id='" + str(allExperimentsId) + "'" + c.execute(updateString) conn.commit() c.close() @@ -541,9 +578,9 @@ def computeViews(dbname): (options, args) = parser.parse_args() if len(args) == 0: - parser.error("No arguments were provided. Please provide full path of log file") + parser.error("No arguments were provided. Please provide full path of log file") - if len(args) == 1: + if len(args) > 0: readBenchmarkLog(options.dbname, args) # If we update the database, we recompute the views as well options.view = True diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index aa59bed3f9..ede31252e9 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -281,45 +281,16 @@ bool BenchmarkExecutor::initializeBenchmarks(const BenchmarkOptions& opts, movei if (!plannerConfigurationsExist(opts.getPlannerConfigurations(), opts.getGroupName())) return false; - try - { - warehouse_ros::DatabaseConnection::Ptr conn = dbloader.loadDatabase(); - conn->setParams(opts.getHostName(), opts.getPort(), 20); - if (conn->connect()) - { - pss_ = new moveit_warehouse::PlanningSceneStorage(conn); - psws_ = new moveit_warehouse::PlanningSceneWorldStorage(conn); - rs_ = new moveit_warehouse::RobotStateStorage(conn); - cs_ = new moveit_warehouse::ConstraintsStorage(conn); - tcs_ = new moveit_warehouse::TrajectoryConstraintsStorage(conn); - } - else - { - ROS_ERROR("Failed to connect to DB"); - return false; - } - } - catch (std::exception& e) - { - ROS_ERROR("Failed to initialize benchmark server: '%s'", e.what()); - return false; - } - std::vector start_states; std::vector path_constraints; std::vector goal_constraints; std::vector traj_constraints; std::vector queries; - bool ok = loadPlanningScene(opts.getSceneName(), scene_msg) && loadStates(opts.getStartStateRegex(), start_states) && - loadPathConstraints(opts.getGoalConstraintRegex(), goal_constraints) && - loadPathConstraints(opts.getPathConstraintRegex(), path_constraints) && - loadTrajectoryConstraints(opts.getTrajectoryConstraintRegex(), traj_constraints) && - loadQueries(opts.getQueryRegex(), opts.getSceneName(), queries); - - if (!ok) + if (!loadBenchmarkQueryData(opts, scene_msg, start_states, path_constraints, goal_constraints, traj_constraints, + queries)) { - ROS_ERROR("Failed to load benchmark stuff"); + ROS_ERROR("Failed to load benchmark query data"); return false; } @@ -429,6 +400,44 @@ bool BenchmarkExecutor::initializeBenchmarks(const BenchmarkOptions& opts, movei return true; } +bool BenchmarkExecutor::loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, + std::vector& start_states, + std::vector& path_constraints, + std::vector& goal_constraints, + std::vector& traj_constraints, + std::vector& queries) +{ + try + { + warehouse_ros::DatabaseConnection::Ptr warehouse_connection = dbloader.loadDatabase(); + warehouse_connection->setParams(opts.getHostName(), opts.getPort(), 20); + if (warehouse_connection->connect()) + { + pss_ = new moveit_warehouse::PlanningSceneStorage(warehouse_connection); + psws_ = new moveit_warehouse::PlanningSceneWorldStorage(warehouse_connection); + rs_ = new moveit_warehouse::RobotStateStorage(warehouse_connection); + cs_ = new moveit_warehouse::ConstraintsStorage(warehouse_connection); + tcs_ = new moveit_warehouse::TrajectoryConstraintsStorage(warehouse_connection); + } + else + { + ROS_ERROR("Failed to connect to DB"); + return false; + } + } + catch (std::exception& e) + { + ROS_ERROR("Failed to initialize benchmark server: '%s'", e.what()); + return false; + } + + return loadPlanningScene(opts.getSceneName(), scene_msg) && loadStates(opts.getStartStateRegex(), start_states) && + loadPathConstraints(opts.getGoalConstraintRegex(), goal_constraints) && + loadPathConstraints(opts.getPathConstraintRegex(), path_constraints) && + loadTrajectoryConstraints(opts.getTrajectoryConstraintRegex(), traj_constraints) && + loadQueries(opts.getQueryRegex(), opts.getSceneName(), queries); +} + void BenchmarkExecutor::shiftConstraintsByOffset(moveit_msgs::Constraints& constraints, const std::vector& offset) { @@ -765,6 +774,9 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, { // This container stores all of the benchmark data for this planner PlannerBenchmarkData planner_data(runs); + // This vector stores all motion plan results for further evaluation + std::vector responses(runs); + std::vector solved(runs); request.planner_id = planner.second[i]; @@ -781,9 +793,8 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, pre_event_fn(request); // Solve problem - planning_interface::MotionPlanDetailedResponse mp_res; ros::WallTime start = ros::WallTime::now(); - bool solved = context->solve(mp_res); + solved[j] = context->solve(responses[j]); double total_time = (ros::WallTime::now() - start).toSec(); // Collect data @@ -791,14 +802,16 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, // Post-run events for (PostRunEventFunction& post_event_fn : post_event_fns_) - post_event_fn(request, mp_res, planner_data[j]); - collectMetrics(planner_data[j], mp_res, solved, total_time); + post_event_fn(request, responses[j], planner_data[j]); + collectMetrics(planner_data[j], responses[j], solved[j], total_time); double metrics_time = (ros::WallTime::now() - start).toSec(); ROS_DEBUG("Spent %lf seconds collecting metrics", metrics_time); ++progress; } + computeAveragePathSimilarities(planner_data, responses, solved); + // Planner completion events for (PlannerCompletionEventFunction& planner_completion_fn : planner_completion_fns_) planner_completion_fn(request, planner_data); @@ -889,6 +902,15 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, metrics["path_" + mp_res.description_[j] + "_clearance REAL"] = moveit::core::toString(clearance); metrics["path_" + mp_res.description_[j] + "_smoothness REAL"] = moveit::core::toString(smoothness); metrics["path_" + mp_res.description_[j] + "_time REAL"] = moveit::core::toString(mp_res.processing_time_[j]); + + if (j == mp_res.trajectory_.size() - 1) + { + metrics["final_path_correct BOOLEAN"] = boost::lexical_cast(correct); + metrics["final_path_length REAL"] = moveit::core::toString(traj_len); + metrics["final_path_clearance REAL"] = moveit::core::toString(clearance); + metrics["final_path_smoothness REAL"] = moveit::core::toString(smoothness); + metrics["final_path_time REAL"] = moveit::core::toString(mp_res.processing_time_[j]); + } process_time -= mp_res.processing_time_[j]; } if (process_time <= 0.0) @@ -897,6 +919,121 @@ void BenchmarkExecutor::collectMetrics(PlannerRunData& metrics, } } +void BenchmarkExecutor::computeAveragePathSimilarities( + PlannerBenchmarkData& planner_data, const std::vector& responses, + const std::vector& solved) +{ + ROS_INFO("Computing result path similarity"); + const size_t result_count = planner_data.size(); + size_t unsolved = std::count_if(solved.begin(), solved.end(), [](bool s) { return !s; }); + std::vector average_distances(responses.size()); + for (size_t first_traj_i = 0; first_traj_i < result_count; ++first_traj_i) + { + // If trajectory was not solved there is no valid average distance so it's set to max double only + if (!solved[first_traj_i]) + { + average_distances[first_traj_i] = std::numeric_limits::max(); + continue; + } + // Iterate all result trajectories that haven't been compared yet + for (size_t second_traj_i = first_traj_i + 1; second_traj_i < result_count; ++second_traj_i) + { + // Ignore if other result has not been solved + if (!solved[second_traj_i]) + continue; + + // Get final trajectories + const robot_trajectory::RobotTrajectory& traj_first = *responses[first_traj_i].trajectory_.back(); + const robot_trajectory::RobotTrajectory& traj_second = *responses[second_traj_i].trajectory_.back(); + + // Compute trajectory distance + double trajectory_distance; + if (!computeTrajectoryDistance(traj_first, traj_second, trajectory_distance)) + continue; + + // Add average distance to counters of both trajectories + average_distances[first_traj_i] += trajectory_distance; + average_distances[second_traj_i] += trajectory_distance; + } + // Normalize average distance by number of actual comparisons + average_distances[first_traj_i] /= result_count - unsolved - 1; + } + + // Store results in planner_data + for (size_t i = 0; i < result_count; ++i) + planner_data[i]["average_waypoint_distance REAL"] = moveit::core::toString(average_distances[i]); +} + +bool BenchmarkExecutor::computeTrajectoryDistance(const robot_trajectory::RobotTrajectory& traj_first, + const robot_trajectory::RobotTrajectory& traj_second, + double& result_distance) +{ + // Abort if trajectories are empty + if (traj_first.empty() || traj_second.empty()) + return false; + + // Waypoint counter + size_t pos_first = 0; + size_t pos_second = 0; + const size_t max_pos_first = traj_first.getWayPointCount() - 1; + const size_t max_pos_second = traj_second.getWayPointCount() - 1; + + // Compute total distance between pairwise waypoints of both trajectories. + // The selection of waypoint pairs is based on what steps results in the minimal distance between the next pair of + // waypoints. We first check what steps are still possible or if we reached the end of the trajectories. Then we + // compute the pairwise waypoint distances of the pairs from increasing both, the first, or the second trajectory. + // Finally we select the pair that results in the minimal distance, summarize the total distance and iterate + // accordingly. After that we compute the average trajectory distance by normalizing over the number of steps. + double total_distance = 0; + size_t steps = 0; + double current_distance = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second)); + while (true) + { + // Keep track of total distance and number of comparisons + total_distance += current_distance; + ++steps; + if (pos_first == max_pos_first && pos_second == max_pos_second) // end reached + break; + + // Determine what steps are still possible + bool can_up_first = pos_first < max_pos_first; + bool can_up_second = pos_second < max_pos_second; + bool can_up_both = can_up_first && can_up_second; + + // Compute pair-wise waypoint distances (increasing both, first, or second trajectories). + double up_both = std::numeric_limits::max(); + double up_first = std::numeric_limits::max(); + double up_second = std::numeric_limits::max(); + if (can_up_both) + up_both = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second + 1)); + if (can_up_first) + up_first = traj_first.getWayPoint(pos_first + 1).distance(traj_second.getWayPoint(pos_second)); + if (can_up_second) + up_second = traj_first.getWayPoint(pos_first).distance(traj_second.getWayPoint(pos_second + 1)); + + // Select actual step, store new distance value and iterate trajectory positions + if (can_up_both && up_both < up_first && up_both < up_second) + { + ++pos_first; + ++pos_second; + current_distance = up_both; + } + else if ((can_up_first && up_first < up_second) || !can_up_second) + { + ++pos_first; + current_distance = up_first; + } + else if (can_up_second) + { + ++pos_second; + current_distance = up_second; + } + } + // Normalize trajectory distance by number of comparison steps + result_distance = total_distance / static_cast(steps); + return true; +} + void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std::string& start_time, double benchmark_duration) { From 3cb561de9efb1a41792baabb9a62d72dcc2c1693 Mon Sep 17 00:00:00 2001 From: Dale Koenig Date: Wed, 31 Jul 2019 22:13:13 +0900 Subject: [PATCH 06/96] JogArm: Remove dependency on move_group node (#1569) --- moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h | 5 +---- moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp | 6 +++--- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h index e610dba2c1..ebc161f263 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h @@ -42,7 +42,6 @@ #include #include -#include #include #include #include @@ -54,14 +53,12 @@ namespace jog_arm class JogCalcs { public: - JogCalcs(const JogArmParameters parameters, JogArmShared& shared_variables, pthread_mutex_t& mutex, + JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_variables, pthread_mutex_t& mutex, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr); protected: ros::NodeHandle nh_; - moveit::planning_interface::MoveGroupInterface move_group_; - sensor_msgs::JointState incoming_jts_; bool cartesianJogCalcs(geometry_msgs::TwistStamped& cmd, JogArmShared& shared_variables, pthread_mutex_t& mutex); diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp index 55c76fb190..6839481eff 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp +++ b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp @@ -42,9 +42,9 @@ namespace jog_arm { // Constructor for the class that handles jogging calculations -JogCalcs::JogCalcs(const JogArmParameters parameters, JogArmShared& shared_variables, pthread_mutex_t& mutex, +JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_variables, pthread_mutex_t& mutex, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr) - : move_group_(parameters.move_group_name), tf_listener_(tf_buffer_), parameters_(parameters) + : tf_listener_(tf_buffer_), parameters_(parameters) { // Publish collision status warning_pub_ = nh_.advertise(parameters_.warning_topic, 1); @@ -72,7 +72,7 @@ JogCalcs::JogCalcs(const JogArmParameters parameters, JogArmShared& shared_varia resetVelocityFilters(); - jt_state_.name = move_group_.getJointNames(); + jt_state_.name = joint_model_group_->getVariableNames(); num_joints_ = jt_state_.name.size(); jt_state_.position.resize(num_joints_); jt_state_.velocity.resize(num_joints_); From bc45aecc465daff77efe2b6c4f92f7c972925bbe Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Wed, 31 Jul 2019 15:23:19 +0200 Subject: [PATCH 07/96] clang-tidy fixup (#1586) --- .../move_group_interface/src/wrap_python_move_group.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index c367477343..b3940182df 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -486,7 +486,7 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer std::string retimeTrajectory(const std::string& ref_state_str, const std::string& traj_str, double velocity_scaling_factor, double acceleration_scaling_factor, - std::string algorithm) + const std::string& algorithm) { // Convert reference state message to object moveit_msgs::RobotState ref_state_msg; From 985e34c2f6e9a91f4fe2bec9168eca366454e238 Mon Sep 17 00:00:00 2001 From: Dave Coleman Date: Fri, 2 Aug 2019 06:42:48 -0400 Subject: [PATCH 08/96] Remove ! from MoveIt name (#1590) --- .docker/README.md | 2 +- .docker/ci/Dockerfile | 2 +- .docker/release/Dockerfile | 2 +- .github/CODEOWNERS | 2 +- .github/config.yml | 4 +- CONTRIBUTING.md | 2 +- MIGRATION.md | 2 +- README.md | 8 ++-- moveit.rosinstall | 4 +- moveit/CHANGELOG.rst | 4 +- moveit/package.xml | 2 +- moveit/scripts/README.md | 4 +- moveit/scripts/create_maintainer_table.py | 2 +- moveit/scripts/create_readme_table.py | 4 +- moveit/scripts/maintainer_table_template.html | 4 +- moveit_commander/README.md | 2 +- .../bin/moveit_commander_cmdline.py | 2 +- moveit_commander/package.xml | 2 +- moveit_core/CMakeLists.txt | 2 +- moveit_core/README.md | 2 +- .../background_processing.h | 2 +- .../controller_manager/controller_manager.h | 12 +++--- .../include/moveit/exceptions/exceptions.h | 2 +- .../dox/constraint_representation.dox | 2 +- moveit_core/package.xml | 4 +- .../planning_interface/planning_interface.h | 4 +- .../planning_scene/dox/planning_scene.dox | 2 +- .../include/moveit/robot_model/robot_model.h | 4 +- .../include/moveit/robot_state/conversions.h | 36 +++++++++--------- .../moveit/sensor_manager/sensor_manager.h | 2 +- moveit_core/transforms/src/transforms.cpp | 2 +- .../moveit/utils/robot_model_test_utils.h | 2 +- .../utils/src/robot_model_test_utils.cpp | 2 +- moveit_experimental/README.md | 4 +- .../jog_arm/config/sia5_simulated_config.yaml | 2 +- .../src/jog_arm/collision_check_thread.cpp | 2 +- .../jog_arm/src/jog_arm/jog_calcs.cpp | 2 +- .../test/arm_setup/config/jog_settings.yaml | 2 +- .../src/kinematics_cache_ros.cpp | 2 +- .../kinematics_constraint_aware.h | 2 +- .../kinematics_request_response.h | 2 +- moveit_experimental/package.xml | 4 +- .../cached_ik_kinematics_plugin/README.md | 2 +- .../ikfast_kinematics_plugin/README.md | 4 +- .../scripts/create_ikfast_moveit_plugin.py | 6 +-- .../ikfast61_moveit_plugin_template.cpp | 6 +-- .../kdl_kinematics_plugin.h | 2 +- .../lma_kinematics_plugin.h | 2 +- moveit_kinematics/package.xml | 4 +- .../srv_kinematics_plugin.h | 4 +- .../test/test_kinematics_plugin.cpp | 2 +- moveit_planners/README.md | 2 +- .../chomp/chomp_interface/CHANGELOG.rst | 2 +- .../chomp/chomp_interface/package.xml | 4 +- .../rrbot_chomp_planning_pipeline.launch.xml | 2 +- .../chomp/chomp_motion_planner/CHANGELOG.rst | 2 +- .../chomp/chomp_motion_planner/package.xml | 2 +- .../chomp/chomp_optimizer_adapter/package.xml | 2 +- moveit_planners/moveit_planners/package.xml | 2 +- moveit_planners/ompl/CHANGELOG.rst | 2 +- .../moveit/ompl_interface/ompl_interface.h | 2 +- .../model_based_state_space.h | 4 +- .../src/detail/state_validity_checker.cpp | 2 +- moveit_planners/ompl/package.xml | 4 +- moveit_plugins/README.md | 2 +- .../moveit_fake_controller_manager/README.md | 4 +- .../package.xml | 2 +- moveit_plugins/moveit_plugins/package.xml | 4 +- .../moveit_ros_control_interface/README.md | 12 +++--- .../moveit_core_plugins.xml | 4 +- .../moveit_ros_control_interface/package.xml | 4 +- .../gripper_controller_handle.h | 2 +- .../package.xml | 2 +- .../src/moveit_simple_controller_manager.cpp | 2 +- moveit_ros/README.md | 4 +- moveit_ros/benchmarks/CHANGELOG.rst | 4 +- moveit_ros/benchmarks/README.md | 2 +- moveit_ros/benchmarks/examples/demo1.yaml | 2 +- moveit_ros/benchmarks/examples/demo2.yaml | 2 +- .../benchmarks/examples/demo_obstacles.yaml | 2 +- .../examples/demo_panda_all_planners.yaml | 2 +- moveit_ros/benchmarks/package.xml | 4 +- .../benchmarks/src/BenchmarkExecutor.cpp | 2 +- moveit_ros/manipulation/package.xml | 4 +- moveit_ros/move_group/package.xml | 2 +- .../test_cancel_before_plan_execution.test | 2 +- moveit_ros/moveit_ros/CHANGELOG.rst | 2 +- moveit_ros/moveit_ros/package.xml | 4 +- moveit_ros/occupancy_map_monitor/package.xml | 4 +- moveit_ros/perception/package.xml | 4 +- .../semantic_world/src/semantic_world.cpp | 2 +- moveit_ros/planning/package.xml | 4 +- .../plan_execution/src/plan_with_sensing.cpp | 2 +- .../src/print_planning_scene_info.cpp | 2 +- .../planning/rdf_loader/src/rdf_loader.cpp | 2 +- .../dox/trajectory_execution.dox | 4 +- .../move_group_interface.h | 2 +- moveit_ros/planning_interface/package.xml | 4 +- .../py_bindings_tools/roscpp_initializer.h | 2 +- moveit_ros/robot_interaction/CHANGELOG.rst | 2 +- moveit_ros/robot_interaction/package.xml | 4 +- .../src/motion_planning_frame_context.cpp | 2 +- .../ui/motion_planning_rviz_plugin_frame.ui | 2 +- moveit_ros/visualization/package.xml | 4 +- .../moveitjoy_module.py | 2 +- moveit_ros/warehouse/CHANGELOG.rst | 2 +- moveit_ros/warehouse/package.xml | 4 +- .../warehouse/src/initialize_demo_db.cpp | 2 +- moveit_runtime/package.xml | 2 +- moveit_setup_assistant/CHANGELOG.rst | 2 +- moveit_setup_assistant/README.md | 2 +- .../tools/moveit_config_data.h | 6 +-- .../launch/setup_assistant.launch | 2 +- moveit_setup_assistant/package.xml | 4 +- .../resources/source/MoveIt_Setup_Asst_Sm.xcf | Bin 375316 -> 375312 bytes .../src/collisions_updater.cpp | 2 +- .../src/tools/moveit_config_data.cpp | 8 ++-- .../src/widgets/author_information_widget.cpp | 6 +-- .../widgets/configuration_files_widget.cpp | 29 +++++++------- .../src/widgets/group_edit_widget.cpp | 4 +- .../src/widgets/perception_widget.cpp | 2 +- .../src/widgets/planning_groups_widget.cpp | 2 +- .../src/widgets/robot_poses_widget.cpp | 6 +-- .../src/widgets/ros_controllers_widget.cpp | 4 +- .../src/widgets/setup_assistant_widget.cpp | 10 ++--- .../src/widgets/simulation_widget.cpp | 2 +- .../src/widgets/start_screen_widget.cpp | 18 ++++----- .../src/widgets/start_screen_widget.h | 4 +- .../launch/chomp_planning_pipeline.launch.xml | 2 +- .../launch/demo.launch | 4 +- .../launch/demo_gazebo.launch | 4 +- .../launch/edit_configuration_package.launch | 2 +- .../launch/ompl_planning_pipeline.launch.xml | 2 +- .../launch/trajectory_execution.launch.xml | 2 +- .../package.xml.template | 2 +- .../test/moveit_config_data_test.cpp | 2 +- 136 files changed, 243 insertions(+), 244 deletions(-) diff --git a/.docker/README.md b/.docker/README.md index a0cf726f20..b24af099ec 100644 --- a/.docker/README.md +++ b/.docker/README.md @@ -1,3 +1,3 @@ -# MoveIt! Docker Containers +# MoveIt Docker Containers For more information see [Continuous Integration and Docker](http://moveit.ros.org/documentation/contributing/continuous_integration.html) documentation. diff --git a/.docker/ci/Dockerfile b/.docker/ci/Dockerfile index dd4c77c91f..830c8abd09 100644 --- a/.docker/ci/Dockerfile +++ b/.docker/ci/Dockerfile @@ -33,7 +33,7 @@ RUN \ clang clang-format-3.9 clang-tidy clang-tools \ ccache && \ # - # Download all dependencies of MoveIt! + # Download all dependencies of MoveIt rosdep update && \ rosdep install -y --from-paths . --ignore-src --rosdistro ${ROS_DISTRO} --as-root=apt:false && \ # diff --git a/.docker/release/Dockerfile b/.docker/release/Dockerfile index e06998b1a2..4611c98b20 100644 --- a/.docker/release/Dockerfile +++ b/.docker/release/Dockerfile @@ -1,5 +1,5 @@ # moveit/moveit:melodic-release -# Full debian-based install of MoveIt! using apt-get +# Full debian-based install of MoveIt using apt-get FROM ros:melodic-ros-base MAINTAINER Dave Coleman dave@picknik.ai diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index a6d58c6912..ca05e3da91 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,4 +1,4 @@ -# MoveIt! is a large project with pull requests being created often. In order +# MoveIt is a large project with pull requests being created often. In order # to ensure quick review turn around time from our maintainer team, we're # leveraging an automated "triage" approach to auto-assign reviews to new pull # requests. If you already know who should review your PR, then you can assign diff --git a/.github/config.yml b/.github/config.yml index fed71ab355..2810cc56b6 100644 --- a/.github/config.yml +++ b/.github/config.yml @@ -11,12 +11,12 @@ newIssueWelcomeComment: > # Comment to be posted to on PRs from first time contributors in your repository newPRWelcomeComment: > - Thanks for helping in improving MoveIt! + Thanks for helping in improving MoveIt # Configuration for first-pr-merge - https://github.com/behaviorbot/first-pr-merge # Comment to be posted to on pull requests merged by a first time user firstPRMergeComment: > - Congrats on getting your first MoveIt! pull request merged and improving open source robotics! + Congrats on getting your first MoveIt pull request merged and improving open source robotics! # It is recommended to include as many gifs and emojis as possible! diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index eeafb30ddf..609c244cf6 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -1,4 +1,4 @@ -# Contributing to MoveIt! +# Contributing to MoveIt Thanks for getting involved! Information on contributing can be found at [http://moveit.ros.org/documentation/contributing/](http://moveit.ros.org/documentation/contributing/) diff --git a/MIGRATION.md b/MIGRATION.md index 05740746a4..5eca3c2660 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -1,6 +1,6 @@ # Migration Notes -API changes in MoveIt! releases +API changes in MoveIt releases ## ROS Noetic (upcoming changes in master) - Extended the return value of `MoveitCommander.MoveGroup.plan()` from `trajectory` to a tuple of `(success, trajectory, planning_time, error_code)` to better match the C++ MoveGroupInterface ([790](https://github.com/ros-planning/moveit/pull/790/)) diff --git a/README.md b/README.md index 0ffd0e0e3b..182da15475 100644 --- a/README.md +++ b/README.md @@ -1,10 +1,10 @@ -MoveIt! Logo +MoveIt Logo -The MoveIt! Motion Planning Framework +The MoveIt Motion Planning Framework Currently we support ROS Indigo, Kinetic, and Melodic. -- [Overview of MoveIt!](http://moveit.ros.org) +- [Overview of MoveIt](http://moveit.ros.org) - [Installation Instructions](http://moveit.ros.org/install/) - [Documentation](http://moveit.ros.org/documentation/) - [Get Involved](http://moveit.ros.org/documentation/contributing/) @@ -32,7 +32,7 @@ build farm | [![Build Status](http://build.ros.org/buildStatus/icon?job=Idev__mo [![Docker Automated build](https://img.shields.io/docker/automated/moveit/moveit.svg?maxAge=2592000)](https://hub.docker.com/r/moveit/moveit/) [![Docker Pulls](https://img.shields.io/docker/pulls/moveit/moveit.svg?maxAge=2592000)](https://hub.docker.com/r/moveit/moveit/) [![Docker Stars](https://img.shields.io/docker/stars/moveit/moveit.svg)](https://registry.hub.docker.com/moveit/moveit/) ## ROS Buildfarm -MoveIt! Package | Indigo Source | Indigo Debian | Kinetic Source | Kinetic Debian | Melodic Source | Melodic Debian +MoveIt Package | Indigo Source | Indigo Debian | Kinetic Source | Kinetic Debian | Melodic Source | Melodic Debian --------------- | ------------- | ------------- | -------------- | -------------- | -------------- | -------------- moveit | [![Build Status](http://build.ros.org/buildStatus/icon?job=Isrc_uT__moveit__ubuntu_trusty__source)](http://build.ros.org/view/Isrc_uT/job/Isrc_uT__moveit__ubuntu_trusty__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ibin_uT64__moveit__ubuntu_trusty_amd64__binary)](http://build.ros.org/view/Ibin_uT64/job/Ibin_uT64__moveit__ubuntu_trusty_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit__ubuntu_bionic_amd64__binary) moveit_chomp_optimizer_adapter | | | | | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_chomp_optimizer_adapter__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_chomp_optimizer_adapter__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_chomp_optimizer_adapter__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_chomp_optimizer_adapter__ubuntu_bionic_amd64__binary) diff --git a/moveit.rosinstall b/moveit.rosinstall index f0ef21afa0..ecab1ac02f 100644 --- a/moveit.rosinstall +++ b/moveit.rosinstall @@ -1,5 +1,5 @@ -# This file is intended for users who want to build MoveIt! from source. -# Used with wstool, users can download source of all packages of MoveIt!. +# This file is intended for users who want to build MoveIt from source. +# Used with wstool, users can download source of all packages of MoveIt. - git: local-name: moveit_msgs uri: https://github.com/ros-planning/moveit_msgs.git diff --git a/moveit/CHANGELOG.rst b/moveit/CHANGELOG.rst index 9f03a155e1..482cd91835 100644 --- a/moveit/CHANGELOG.rst +++ b/moveit/CHANGELOG.rst @@ -64,7 +64,7 @@ Changelog for package moveit 0.10.2 (2018-10-24) ------------------- -* [fix] Text refrences to MoveIt! (`#1020 `_) +* [fix] Text refrences to MoveIt (`#1020 `_) * [fix] Eigen alignment issuses due to missing aligned allocation (`#1039 `_) * [fix][chomp] changelogs: migration from tf -> tf2 only accidentally became part of 0.9.12's changelog * [fix] Chomp package handling issue `#1086 `_ that was introduced in `ubi-agni/hotfix-#1012 `_ @@ -82,7 +82,7 @@ Changelog for package moveit * [capability][chomp] Failure recovery options for CHOMP by tweaking parameters (`#987 `_) * [capability] New screen for automatically generating interfaces to low level controllers(`#951 `_, `#994 `_, `#908 `_) * [capability][moveit_setup_assistant] Perception screen for using laser scanner point clouds. (`#969 `_) -* [enhancement][GUI][moveit_setup_assistant] Logo for MoveIt! 2.0, cleanup appearance (`#1059 `_) +* [enhancement][GUI][moveit_setup_assistant] Logo for MoveIt 2.0, cleanup appearance (`#1059 `_) * [enhancement][GUI][moveit_setup_assistant] added a setup assistant window icon (`#1028 `_) * [capability][chomp] Addition of CHOMP planning adapter for optimizing result of other planners (`#1012 `_) * [capability][chomp] Failure recovery options for CHOMP by tweaking parameters (`#987 `_) diff --git a/moveit/package.xml b/moveit/package.xml index 0a60b4860e..5a50dbd315 100644 --- a/moveit/package.xml +++ b/moveit/package.xml @@ -2,7 +2,7 @@ moveit 1.0.1 - Meta package that contains all essential package of MoveIt!. Until Summer 2016 MoveIt! had been developed over multiple repositories, where developers' usability and maintenance effort was non-trivial. See the detailed discussion for the merge of several repositories. + Meta package that contains all essential package of MoveIt. Until Summer 2016 MoveIt had been developed over multiple repositories, where developers' usability and maintenance effort was non-trivial. See the detailed discussion for the merge of several repositories. Dave Coleman Michael Ferguson Michael Görner diff --git a/moveit/scripts/README.md b/moveit/scripts/README.md index ddc705b86f..e2da938586 100644 --- a/moveit/scripts/README.md +++ b/moveit/scripts/README.md @@ -1,8 +1,8 @@ -# Utility Scripts for MoveIt! +# Utility Scripts for MoveIt ## README Markdown Buildfarm Table Generator -This Python script will generate Github-style Markdown table with Jenkins badges for every package recursively from the current folder. It will order all packages alphabetically, but start with all MoveIt! packages first. For generating an updated README for a new ROS distribution, first update the `create_readme_table.py` script and add/remove the current MoveIt!-supported ROS distros and their corresponding Ubuntu distribution in the specified Python dictionary. Then, in the main MoveIt! `README.md` file, remove the "## ROS Buildfarm" header and the following table. Finally, from your catkin workspace with every MoveIt! package, run the `create_readme_table.py` script. For example: +This Python script will generate Github-style Markdown table with Jenkins badges for every package recursively from the current folder. It will order all packages alphabetically, but start with all MoveIt packages first. For generating an updated README for a new ROS distribution, first update the `create_readme_table.py` script and add/remove the current MoveIt-supported ROS distros and their corresponding Ubuntu distribution in the specified Python dictionary. Then, in the main MoveIt `README.md` file, remove the "## ROS Buildfarm" header and the following table. Finally, from your catkin workspace with every MoveIt package, run the `create_readme_table.py` script. For example: cd ~/ws_moveit/src python moveit/moveit/scripts/create_readme_table.py >> moveit/README.md diff --git a/moveit/scripts/create_maintainer_table.py b/moveit/scripts/create_maintainer_table.py index af7615c2a9..1557530ee2 100644 --- a/moveit/scripts/create_maintainer_table.py +++ b/moveit/scripts/create_maintainer_table.py @@ -98,7 +98,7 @@ def populate_package_data(path, package): def list_moveit_packages(): """ - Creates MoveIt! List + Creates MoveIt List """ output = '' packages = find_packages(os.getcwd()) diff --git a/moveit/scripts/create_readme_table.py b/moveit/scripts/create_readme_table.py index 9a5af08554..e854893b0b 100644 --- a/moveit/scripts/create_readme_table.py +++ b/moveit/scripts/create_readme_table.py @@ -11,7 +11,7 @@ def create_header(ros_ubuntu_dict): ros_distros = sorted(ros_ubuntu_dict.keys()) section_header = "## ROS Buildfarm\n" - header="MoveIt! Package" + header="MoveIt Package" header_lines = '-'*len(header) for ros in ros_distros: source = ' '.join([ros.capitalize(), "Source"]) @@ -49,7 +49,7 @@ def create_line(package, ros_ubuntu_dict): def create_moveit_buildfarm_table(): """ - Creates MoveIt! buildfarm badge table + Creates MoveIt buildfarm badge table """ # Update the following dictionary with the appropriate ROS-Ubuntu # combinations for supported distribitions. For instance, in Noetic, diff --git a/moveit/scripts/maintainer_table_template.html b/moveit/scripts/maintainer_table_template.html index b5c94f4020..584b1d68d6 100644 --- a/moveit/scripts/maintainer_table_template.html +++ b/moveit/scripts/maintainer_table_template.html @@ -2,7 +2,7 @@ - MoveIt! Package Tracking + MoveIt Package Tracking @@ -23,7 +23,7 @@ -

MoveIt! Package Tracking

+

MoveIt Package Tracking

diff --git a/moveit_commander/README.md b/moveit_commander/README.md index ecd51ed3b1..1b8f538576 100644 --- a/moveit_commander/README.md +++ b/moveit_commander/README.md @@ -1 +1 @@ -# MoveIt! Commander +# MoveIt Commander diff --git a/moveit_commander/bin/moveit_commander_cmdline.py b/moveit_commander/bin/moveit_commander_cmdline.py index eb3c524c74..2dffaa7630 100755 --- a/moveit_commander/bin/moveit_commander_cmdline.py +++ b/moveit_commander/bin/moveit_commander_cmdline.py @@ -151,7 +151,7 @@ def sigint_handler(signal, frame): rospy.init_node('move_group_interface_cmdline', anonymous=True, disable_signals=True) parser = argparse.ArgumentParser(usage = """%(prog)s [options] []""", - description = "Command Line Interface to MoveIt!") + description = "Command Line Interface to MoveIt") parser.add_argument("-i", "--interactive", action="store_true", dest="interactive", default=True, help="Run the command processing script in interactive mode (default)") parser.add_argument("-s", "--service", action="store_true", dest="service", default=False, diff --git a/moveit_commander/package.xml b/moveit_commander/package.xml index 6680232adc..a962c6a2df 100644 --- a/moveit_commander/package.xml +++ b/moveit_commander/package.xml @@ -7,7 +7,7 @@ Michael Görner Robert Haschke - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_core/CMakeLists.txt b/moveit_core/CMakeLists.txt index 9fd0c3bc6e..4e450735db 100644 --- a/moveit_core/CMakeLists.txt +++ b/moveit_core/CMakeLists.txt @@ -174,7 +174,7 @@ string(REGEX REPLACE "^[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_MINOR "${${PROJ string(REGEX REPLACE "^[0-9]+\\.[0-9]+\\.([0-9]+).*" "\\1" MOVEIT_VERSION_PATCH "${${PROJECT_NAME}_VERSION}") set(MOVEIT_VERSION_EXTRA "Alpha") set(MOVEIT_VERSION "${MOVEIT_VERSION_MAJOR}.${MOVEIT_VERSION_MINOR}.${MOVEIT_VERSION_PATCH}-${MOVEIT_VERSION_EXTRA}") -message(STATUS " *** Building MoveIt! ${MOVEIT_VERSION} ***") +message(STATUS " *** Building MoveIt ${MOVEIT_VERSION} ***") configure_file("version/version.h.in" "${VERSION_FILE_PATH}/moveit/version.h") #catkin_lint: ignore_once external_file install(FILES "${VERSION_FILE_PATH}/moveit/version.h" DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}/moveit) diff --git a/moveit_core/README.md b/moveit_core/README.md index 2a54efedd4..5e602a457c 100644 --- a/moveit_core/README.md +++ b/moveit_core/README.md @@ -1,4 +1,4 @@ -# MoveIt! Core +# MoveIt Core This repository includes core libraries used by MoveIt: - representation of kinematic models diff --git a/moveit_core/background_processing/include/moveit/background_processing/background_processing.h b/moveit_core/background_processing/include/moveit/background_processing/background_processing.h index 30cd7380ae..270be22622 100644 --- a/moveit_core/background_processing/include/moveit/background_processing/background_processing.h +++ b/moveit_core/background_processing/include/moveit/background_processing/background_processing.h @@ -47,7 +47,7 @@ namespace moveit { /** \brief This namespace includes classes and functions that are - helpful in the implementation of other MoveIt! components. This is + helpful in the implementation of other MoveIt components. This is not code specific to the functionality provided by MoveIt. */ namespace tools { diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index da193cb0c2..2a32ff04a8 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -42,7 +42,7 @@ #include #include -/// Namespace for the base class of a MoveIt! controller manager +/// Namespace for the base class of a MoveIt controller manager namespace moveit_controller_manager { /// The reported execution status @@ -101,7 +101,7 @@ struct ExecutionStatus MOVEIT_CLASS_FORWARD(MoveItControllerHandle); -/** \brief MoveIt! sends commands to a controller via a handle that satisfies this interface. */ +/** \brief MoveIt sends commands to a controller via a handle that satisfies this interface. */ class MoveItControllerHandle { public: @@ -149,7 +149,7 @@ class MoveItControllerHandle MOVEIT_CLASS_FORWARD(MoveItControllerManager); -/** @brief MoveIt! does not enforce how controllers are implemented. +/** @brief MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt, this interface needs to be implemented. The main purpose of this interface is to expose the set of known controllers and potentially to allow activating and deactivating them, if multiple controllers are available. @@ -157,7 +157,7 @@ MOVEIT_CLASS_FORWARD(MoveItControllerManager); class MoveItControllerManager { public: - /** \brief Each controller known to MoveIt! has a state. This + /** \brief Each controller known to MoveIt has a state. This structure describes that controller's state. */ struct ControllerState { @@ -165,12 +165,12 @@ class MoveItControllerManager { } - /** \brief A controller can be active or inactive. This means that MoveIt! could activate the controller when + /** \brief A controller can be active or inactive. This means that MoveIt could activate the controller when needed, and de-activate controllers that overlap (control the same set of joints) */ bool active_; /** \brief It is often the case that multiple controllers could be used to execute a motion. Marking a controller as - default makes MoveIt! prefer this controller when multiple options are available. */ + default makes MoveIt prefer this controller when multiple options are available. */ bool default_; }; diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 2dd4f93464..7918eef07d 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -39,7 +39,7 @@ #include -/** \brief Main namespace for MoveIt! */ +/** \brief Main namespace for MoveIt */ namespace moveit { /** \brief This may be thrown during construction of objects if errors occur */ diff --git a/moveit_core/kinematic_constraints/dox/constraint_representation.dox b/moveit_core/kinematic_constraints/dox/constraint_representation.dox index 886a3100e9..d786835f0c 100644 --- a/moveit_core/kinematic_constraints/dox/constraint_representation.dox +++ b/moveit_core/kinematic_constraints/dox/constraint_representation.dox @@ -1,7 +1,7 @@ /** \page constraint_representation Representation and Evaluation of Constraints -Constraints are integral component of MoveIt! and they are used both to constrain robot motion as well as to define planning goals. There following set of constraints are defined in the kinematic_constraints namespace: +Constraints are integral component of MoveIt and they are used both to constrain robot motion as well as to define planning goals. There following set of constraints are defined in the kinematic_constraints namespace: - kinematic_constraints::JointConstraint - kinematic_constraints::OrientationConstraint - kinematic_constraints::PositionConstraint diff --git a/moveit_core/package.xml b/moveit_core/package.xml index b12b48f6f3..121f19f3b3 100644 --- a/moveit_core/package.xml +++ b/moveit_core/package.xml @@ -1,7 +1,7 @@ moveit_core 1.0.1 - Core libraries used by MoveIt! + Core libraries used by MoveIt Ioan Sucan Sachin Chitta Acorn Pooley @@ -9,7 +9,7 @@ Dave Coleman Michael Görner Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD http://moveit.ros.org diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 68214f4a92..93748f43ef 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -48,7 +48,7 @@ namespace planning_scene MOVEIT_CLASS_FORWARD(PlanningScene); } -/** \brief This namespace includes the base class for MoveIt! planners */ +/** \brief This namespace includes the base class for MoveIt planners */ namespace planning_interface { /** @@ -147,7 +147,7 @@ class PlanningContext MOVEIT_CLASS_FORWARD(PlannerManager); -/** \brief Base class for a MoveIt! planner */ +/** \brief Base class for a MoveIt planner */ class PlannerManager { public: diff --git a/moveit_core/planning_scene/dox/planning_scene.dox b/moveit_core/planning_scene/dox/planning_scene.dox index 447b8f52b7..8bd31301b4 100644 --- a/moveit_core/planning_scene/dox/planning_scene.dox +++ b/moveit_core/planning_scene/dox/planning_scene.dox @@ -2,7 +2,7 @@ \page planning_scene_overview Planning Scene -The planning scene (planning_scene::PlanningScene) is the central class for motion planning in MoveIt!. A planning scene represents all the information needed to compute motion plans: The robot's current state, its representation (geometric, kinematic, dynamic) and the world representation. Using this information, things like forward kinematics, inverse kinematics, evaluation of constraints, collision checking, are all possible. +The planning scene (planning_scene::PlanningScene) is the central class for motion planning in MoveIt. A planning scene represents all the information needed to compute motion plans: The robot's current state, its representation (geometric, kinematic, dynamic) and the world representation. Using this information, things like forward kinematics, inverse kinematics, evaluation of constraints, collision checking, are all possible. The planning_scene::PlanningScene class is tightly connected to the planning_scene_monitor::PlannningSceneMonitor class, which maintains a planning scene using information from the ROS Parameter Server and subscription to topics. diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 2131a6f1a8..5e0b98061d 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -54,10 +54,10 @@ #include #include -/** \brief Main namespace for MoveIt! */ +/** \brief Main namespace for MoveIt */ namespace moveit { -/** \brief Core components of MoveIt! */ +/** \brief Core components of MoveIt */ namespace core { MOVEIT_CLASS_FORWARD(RobotModel); diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index dadd10adbc..655329acff 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -47,18 +47,18 @@ namespace moveit namespace core { /** - * @brief Convert a joint state to a MoveIt! robot state + * @brief Convert a joint state to a MoveIt robot state * @param joint_state The input joint state to be converted - * @param state The resultant MoveIt! robot state + * @param state The resultant MoveIt robot state * @return True if successful, false if failed for any reason */ bool jointStateToRobotState(const sensor_msgs::JointState& joint_state, RobotState& state); /** - * @brief Convert a robot state msg (with accompanying extra transforms) to a MoveIt! robot state + * @brief Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state * @param tf An instance of a transforms object * @param robot_state The input robot state msg - * @param state The resultant MoveIt! robot state + * @param state The resultant MoveIt robot state * @param copy_attached_bodies Flag to include attached objects in robot state copy * @return True if successful, false if failed for any reason */ @@ -66,9 +66,9 @@ bool robotStateMsgToRobotState(const Transforms& tf, const moveit_msgs::RobotSta bool copy_attached_bodies = true); /** - * @brief Convert a robot state msg (with accompanying extra transforms) to a MoveIt! robot state + * @brief Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state * @param robot_state The input robot state msg - * @param state The resultant MoveIt! robot state + * @param state The resultant MoveIt robot state * @param copy_attached_bodies Flag to include attached objects in robot state copy * @return True if successful, false if failed for any reason */ @@ -76,8 +76,8 @@ bool robotStateMsgToRobotState(const moveit_msgs::RobotState& robot_state, Robot bool copy_attached_bodies = true); /** - * @brief Convert a MoveIt! robot state to a robot state message - * @param state The input MoveIt! robot state object + * @brief Convert a MoveIt robot state to a robot state message + * @param state The input MoveIt robot state object * @param robot_state The resultant RobotState *message * @param copy_attached_bodies Flag to include attached objects in robot state copy */ @@ -86,33 +86,33 @@ void robotStateToRobotStateMsg(const RobotState& state, moveit_msgs::RobotState& /** * @brief Convert AttachedBodies to AttachedCollisionObjects - * @param attached_bodies The input MoveIt! attached body objects + * @param attached_bodies The input MoveIt attached body objects * @param attached_collision_objs The resultant AttachedCollisionObject messages */ void attachedBodiesToAttachedCollisionObjectMsgs( const std::vector& attached_bodies, std::vector& attached_collision_objs); /** - * @brief Convert a MoveIt! robot state to a joint state message - * @param state The input MoveIt! robot state object + * @brief Convert a MoveIt robot state to a joint state message + * @param state The input MoveIt robot state object * @param robot_state The resultant JointState message */ void robotStateToJointStateMsg(const RobotState& state, sensor_msgs::JointState& joint_state); /** - * @brief Convert a joint trajectory point to a MoveIt! robot state + * @brief Convert a joint trajectory point to a MoveIt robot state * @param joint_trajectory The input msg * @param point_id The index of the trajectory point in the joint trajectory. - * @param state The resultant MoveIt! robot state + * @param state The resultant MoveIt robot state * @return True if successful, false if failed for any reason */ bool jointTrajPointToRobotState(const trajectory_msgs::JointTrajectory& trajectory, std::size_t point_id, RobotState& state); /** - * @brief Convert a MoveIt! robot state to common separated values (CSV) on a single line that is + * @brief Convert a MoveIt robot state to common separated values (CSV) on a single line that is * outputted to a stream e.g. for file saving - * @param state - The input MoveIt! robot state object + * @param state - The input MoveIt robot state object * @param out - a file stream, or any other stream * @param include_header - flag to prefix the output with a line of joint names. * @param separator - allows to override the comma seperator with any symbol, such as a white space @@ -121,9 +121,9 @@ void robotStateToStream(const RobotState& state, std::ostream& out, bool include const std::string& separator = ","); /** - * @brief Convert a MoveIt! robot state to common separated values (CSV) on a single line that is + * @brief Convert a MoveIt robot state to common separated values (CSV) on a single line that is * outputted to a stream e.g. for file saving. This version can order by joint model groups - * @param state - The input MoveIt! robot state object + * @param state - The input MoveIt robot state object * @param out - a file stream, or any other stream * @param joint_group_ordering - output joints based on ordering of joint groups * @param include_header - flag to prefix the output with a line of joint names. @@ -135,7 +135,7 @@ void robotStateToStream(const RobotState& state, std::ostream& out, /** * \brief Convert a string of joint values from a file (CSV) or input source into a RobotState - * @param state - the output MoveIt! robot state object + * @param state - the output MoveIt robot state object * @param line - the input string of joint values * @param separator - allows to override the comma seperator with any symbol, such as a white space * \return true on success diff --git a/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h b/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h index 66c05d4036..a8f1a1615b 100644 --- a/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h +++ b/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h @@ -43,7 +43,7 @@ #include #include -/// Namespace for the base class of a MoveIt! sensor manager +/// Namespace for the base class of a MoveIt sensor manager namespace moveit_sensor_manager { /** \brief Define the frame of reference and the frustum of a sensor (usually this is a visual sensor) */ diff --git a/moveit_core/transforms/src/transforms.cpp b/moveit_core/transforms/src/transforms.cpp index b853319172..190fb10d0d 100644 --- a/moveit_core/transforms/src/transforms.cpp +++ b/moveit_core/transforms/src/transforms.cpp @@ -47,7 +47,7 @@ Transforms::Transforms(const std::string& target_frame) : target_frame_(target_f { boost::trim(target_frame_); if (target_frame_.empty()) - ROS_ERROR_NAMED("transforms", "The target frame for MoveIt! Transforms cannot be empty."); + ROS_ERROR_NAMED("transforms", "The target frame for MoveIt Transforms cannot be empty."); else { transforms_map_[target_frame_] = Eigen::Isometry3d::Identity(); diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index fa9bbf989c..079cf49749 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -14,7 +14,7 @@ * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. - * * Neither the name of MoveIt! nor the names of its + * * Neither the name of MoveIt nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 9a083176a3..50221182ec 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -14,7 +14,7 @@ * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. - * * Neither the name of MoveIt! nor the names of its + * * Neither the name of MoveIt nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * diff --git a/moveit_experimental/README.md b/moveit_experimental/README.md index 2d250777f5..7ef8ed18c2 100644 --- a/moveit_experimental/README.md +++ b/moveit_experimental/README.md @@ -1,5 +1,5 @@ -# Experimental Packages for MoveIt! +# Experimental Packages for MoveIt -This repository includes possibly broken/unmaintained/unfinished libraries that are being worked on or have been worked on in the past. They are not part of MoveIt! officially. +This repository includes possibly broken/unmaintained/unfinished libraries that are being worked on or have been worked on in the past. They are not part of MoveIt officially. No support is offered for code in this repository, but you are welcome to use it if you see fit. diff --git a/moveit_experimental/jog_arm/config/sia5_simulated_config.yaml b/moveit_experimental/jog_arm/config/sia5_simulated_config.yaml index 0ce6b2614e..3a0a253ce0 100644 --- a/moveit_experimental/jog_arm/config/sia5_simulated_config.yaml +++ b/moveit_experimental/jog_arm/config/sia5_simulated_config.yaml @@ -14,7 +14,7 @@ move_group_name: arm # Often 'manipulator' or 'arm' lower_singularity_threshold: 15 # Start decelerating when the condition number hits this (close to singularity). Larger --> closer to singularity hard_stop_singularity_threshold: 30 # Stop when the condition number hits this. Larger --> closer to singularity collision_proximity_threshold: 0.03 # Start decelerating when a collision is this far [m] -planning_frame: base_link # The MoveIt! planning frame. Often 'base_link' +planning_frame: base_link # The MoveIt planning frame. Often 'base_link' low_pass_filter_coeff: 2. # Larger-> more smoothing of jog commands, but more lag. publish_period: 0.008 # 1/Nominal publish rate [seconds] publish_delay: 0.005 # delay between calculation and execution start of command diff --git a/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp b/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp index 47ecd0b10d..3b165a3e95 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp +++ b/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp @@ -49,7 +49,7 @@ CollisionCheckThread::CollisionCheckThread(const jog_arm::JogArmParameters param // If user specified true in yaml file if (parameters.check_collisions) { - // MoveIt! Setup + // MoveIt Setup while (ros::ok() && !model_loader_ptr) { ROS_WARN_THROTTLE_NAMED(5, LOGNAME, "Waiting for a non-null robot_model_loader pointer"); diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp index 6839481eff..2690865c67 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp +++ b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp @@ -49,7 +49,7 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari // Publish collision status warning_pub_ = nh_.advertise(parameters_.warning_topic, 1); - // MoveIt! Setup + // MoveIt Setup while (ros::ok() && !model_loader_ptr) { ROS_WARN_THROTTLE_NAMED(5, LOGNAME, "Waiting for a non-null robot_model_loader pointer"); diff --git a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml b/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml index 15668db878..d9e3ff0db3 100644 --- a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml +++ b/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml @@ -14,7 +14,7 @@ move_group_name: panda_arm # Often 'manipulator' or 'arm' lower_singularity_threshold: 30 # Start decelerating when the condition number hits this (close to singularity). Larger --> closer to singularity hard_stop_singularity_threshold: 45 # Stop when the condition number hits this. Larger --> closer to singularity collision_proximity_threshold: 0.03 # Start decelerating when a collision is this far [m] -planning_frame: base_link # The MoveIt! planning frame. Often 'base_link' +planning_frame: base_link # The MoveIt planning frame. Often 'base_link' low_pass_filter_coeff: 2. # Larger-> more smoothing to jog commands, but more lag. publish_period: 0.01 # 1/Nominal publish rate [seconds] publish_delay: 0.005 # delay between calculation and execution start of command diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp index 40342b1d31..edc2f0cb64 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/src/kinematics_cache_ros.cpp @@ -40,7 +40,7 @@ // ROS #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index 4e8ab4348d..2ec2f70299 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -51,7 +51,7 @@ // Plugin #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h index b2f62e462b..6d2086a08a 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h @@ -44,7 +44,7 @@ // ROS msgs #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_experimental/package.xml b/moveit_experimental/package.xml index e34d9ee6dc..222652ff6a 100644 --- a/moveit_experimental/package.xml +++ b/moveit_experimental/package.xml @@ -1,8 +1,8 @@ moveit_experimental 1.0.1 - Experimental packages for MoveIt! - MoveIt! Release Team + Experimental packages for MoveIt + MoveIt Release Team BSD http://moveit.ros.org diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/README.md b/moveit_kinematics/cached_ik_kinematics_plugin/README.md index 571d53ab2c..77aa5697cd 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/README.md +++ b/moveit_kinematics/cached_ik_kinematics_plugin/README.md @@ -46,7 +46,7 @@ This illustrates two points: (1) if the IK solver is slow, significant improveme Below is a complete list of all arguments: -- `robot`: the name of the corresponding MoveIt! config package +- `robot`: the name of the corresponding MoveIt config package - `group`: the joint group to measure (by default performance is reported for all joint groups) - `tip`: the name of the end effector (by default the default end effectors are used) - `num`: the number of IK calls per joint group diff --git a/moveit_kinematics/ikfast_kinematics_plugin/README.md b/moveit_kinematics/ikfast_kinematics_plugin/README.md index 2f90c02007..c29d897011 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/README.md +++ b/moveit_kinematics/ikfast_kinematics_plugin/README.md @@ -1,9 +1,9 @@ -MoveIt! IKFast +MoveIt IKFast ========== * Authors: Dave Coleman, CU Boulder; Jeremy Zoss, SwRI; David Butterworth, KAIST, Mathias Lüdtke, Fraunhofer IPA * Date: 5/24/2013 -Generates a IKFast kinematics plugin for MoveIt! using [OpenRave](http://openrave.org/) generated cpp files. +Generates a IKFast kinematics plugin for MoveIt using [OpenRave](http://openrave.org/) generated cpp files. Tested on ROS Hydro and greater with Catkin using OpenRave 0.8 with a 6dof and 7dof robot arm manipulator. Does not work with greater than 7dof. diff --git a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py index ab5abaaead..e9ce8770d7 100755 --- a/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py +++ b/moveit_kinematics/ikfast_kinematics_plugin/scripts/create_ikfast_moveit_plugin.py @@ -1,7 +1,7 @@ #! /usr/bin/env python from __future__ import print_function ''' -IKFast Plugin Generator for MoveIt! +IKFast Plugin Generator for MoveIt Creates a kinematics plugin using the output of IKFast from OpenRAVE. This plugin and the move_group node can be used as a general @@ -71,13 +71,13 @@ def get_pkg_dir(pkg_name): def create_parser(): parser = argparse.ArgumentParser( - description="Generate an IKFast MoveIt! kinematic plugin") + description="Generate an IKFast MoveIt kinematic plugin") parser.add_argument("robot_name", help="The name of your robot") parser.add_argument("planning_group_name", help="The name of the planning group for which your IKFast solution was generated") parser.add_argument("ikfast_plugin_pkg", - help="The name of the MoveIt! IKFast Kinematics Plugin to be created/updated") + help="The name of the MoveIt IKFast Kinematics Plugin to be created/updated") parser.add_argument("base_link_name", help="The name of the base link that was used when generating your IKFast solution") parser.add_argument("eef_link_name", diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp index c76082e880..b2fd03982a 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp +++ b/moveit_kinematics/ikfast_kinematics_plugin/templates/ikfast61_moveit_plugin_template.cpp @@ -34,11 +34,11 @@ *********************************************************************/ /* - * IKFast Kinematics Solver Plugin for MoveIt! wrapping an ikfast solver from OpenRAVE. + * IKFast Kinematics Solver Plugin for MoveIt wrapping an ikfast solver from OpenRAVE. * * AUTO-GENERATED by create_ikfast_moveit_plugin.py in moveit_kinematics package. * - * This file, including the ikfast cpp from OpenRAVE below, forms a MoveIt! kinematics plugin. + * This file, including the ikfast cpp from OpenRAVE below, forms a MoveIt kinematics plugin. */ #include @@ -940,7 +940,7 @@ bool IKFastKinematicsPlugin::searchPositionIK(const geometry_msgs::Pose& ik_pose if (!consistency_limits.empty()) { - // MoveIt! replaced consistency_limit (scalar) w/ consistency_limits (vector) + // MoveIt replaced consistency_limit (scalar) w/ consistency_limits (vector) // Assume [0]th free_params element for now. Probably wrong. double max_limit = fmin(joint_max_vector_[free_params_[0]], initial_guess + consistency_limits[free_params_[0]]); double min_limit = fmax(joint_min_vector_[free_params_[0]], initial_guess - consistency_limits[free_params_[0]]); diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 6f094a50e0..9c4a150045 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -53,7 +53,7 @@ #include #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h b/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h index 996080593a..0ec6c0667d 100644 --- a/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h +++ b/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h @@ -53,7 +53,7 @@ #include #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_kinematics/package.xml b/moveit_kinematics/package.xml index 649b3ef22a..64ddccb0b9 100644 --- a/moveit_kinematics/package.xml +++ b/moveit_kinematics/package.xml @@ -2,7 +2,7 @@ moveit_kinematics 1.0.1 - Package for all inverse kinematics solvers in MoveIt! + Package for all inverse kinematics solvers in MoveIt Dave Coleman Ioan Sucan @@ -11,7 +11,7 @@ Dave Coleman G.A. vd. Hoorn Jorge Nicho - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index b19d1e880a..50449662fe 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -33,7 +33,7 @@ *********************************************************************/ /* Author: Dave Coleman, Masaki Murooka - Desc: Connects MoveIt! to any inverse kinematics solver via a ROS service call + Desc: Connects MoveIt to any inverse kinematics solver via a ROS service call Supports planning groups with multiple tip frames \todo: better support for mimic joints \todo: better support for redundant joints @@ -55,7 +55,7 @@ #include #include -// MoveIt! +// MoveIt #include #include diff --git a/moveit_kinematics/test/test_kinematics_plugin.cpp b/moveit_kinematics/test/test_kinematics_plugin.cpp index 682a519909..1235bfd9f9 100644 --- a/moveit_kinematics/test/test_kinematics_plugin.cpp +++ b/moveit_kinematics/test/test_kinematics_plugin.cpp @@ -43,7 +43,7 @@ #include #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_planners/README.md b/moveit_planners/README.md index 0f0f685d07..5d35579eac 100644 --- a/moveit_planners/README.md +++ b/moveit_planners/README.md @@ -1,3 +1,3 @@ -# MoveIt! Planners +# MoveIt Planners Interfaces for the motion planning libraries used in MoveIt diff --git a/moveit_planners/chomp/chomp_interface/CHANGELOG.rst b/moveit_planners/chomp/chomp_interface/CHANGELOG.rst index 3b2e6e9912..7184007695 100644 --- a/moveit_planners/chomp/chomp_interface/CHANGELOG.rst +++ b/moveit_planners/chomp/chomp_interface/CHANGELOG.rst @@ -48,7 +48,7 @@ Changelog for package chomp_interface 0.10.1 (2018-05-25) ------------------- * [fix] dependencies for chomp interface test (`#778 `_) -* [maintenance] MoveIt! tf2 migration (`#830 `_) +* [maintenance] MoveIt tf2 migration (`#830 `_) * Contributors: Bence Magyar, Dave Coleman, Ian McMahon, Mikael Arguedas, Robert Haschke, Stephan, Will Baker 0.9.11 (2017-12-25) diff --git a/moveit_planners/chomp/chomp_interface/package.xml b/moveit_planners/chomp/chomp_interface/package.xml index e7f232010e..bc27808754 100644 --- a/moveit_planners/chomp/chomp_interface/package.xml +++ b/moveit_planners/chomp/chomp_interface/package.xml @@ -1,13 +1,13 @@ moveit_planners_chomp - The interface for using CHOMP within MoveIt! + The interface for using CHOMP within MoveIt 1.0.1 Gil Jones Chittaranjan Srinivas Swaminathan Dave Coleman - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_planners/chomp/chomp_interface/test/rrbot_chomp_planning_pipeline.launch.xml b/moveit_planners/chomp/chomp_interface/test/rrbot_chomp_planning_pipeline.launch.xml index b3146c917b..4b3a1f6f54 100644 --- a/moveit_planners/chomp/chomp_interface/test/rrbot_chomp_planning_pipeline.launch.xml +++ b/moveit_planners/chomp/chomp_interface/test/rrbot_chomp_planning_pipeline.launch.xml @@ -1,5 +1,5 @@ - + diff --git a/moveit_planners/chomp/chomp_motion_planner/CHANGELOG.rst b/moveit_planners/chomp/chomp_motion_planner/CHANGELOG.rst index 0dc05a2151..d32082addf 100644 --- a/moveit_planners/chomp/chomp_motion_planner/CHANGELOG.rst +++ b/moveit_planners/chomp/chomp_motion_planner/CHANGELOG.rst @@ -50,7 +50,7 @@ Changelog for package chomp_motion_planner 0.10.1 (2018-05-25) ------------------- * [fix] for chomp fixed base joint bug (`#870 `_) -* [maintenance] MoveIt! tf2 migration (`#830 `_) +* [maintenance] MoveIt tf2 migration (`#830 `_) * [maintenance] switch to ROS_LOGGER from CONSOLE_BRIDGE (`#874 `_) * Contributors: Bence Magyar, Dave Coleman, Ian McMahon, Mike Lautman, Xiaojian Ma diff --git a/moveit_planners/chomp/chomp_motion_planner/package.xml b/moveit_planners/chomp/chomp_motion_planner/package.xml index 8abb126185..81c05a1bf6 100644 --- a/moveit_planners/chomp/chomp_motion_planner/package.xml +++ b/moveit_planners/chomp/chomp_motion_planner/package.xml @@ -7,7 +7,7 @@ Mrinal Kalakrishnan Chittaranjan Srinivas Swaminathan - MoveIt! Release Team + MoveIt Release Team BSD http://ros.org/wiki/chomp_motion_planner diff --git a/moveit_planners/chomp/chomp_optimizer_adapter/package.xml b/moveit_planners/chomp/chomp_optimizer_adapter/package.xml index f5a6d016a7..4861c4e43c 100644 --- a/moveit_planners/chomp/chomp_optimizer_adapter/package.xml +++ b/moveit_planners/chomp/chomp_optimizer_adapter/package.xml @@ -6,7 +6,7 @@ 1.0.1 Raghavender Sahdev Raghavender Sahdev - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_planners/moveit_planners/package.xml b/moveit_planners/moveit_planners/package.xml index 77d65918bf..a3ef9a50aa 100644 --- a/moveit_planners/moveit_planners/package.xml +++ b/moveit_planners/moveit_planners/package.xml @@ -6,7 +6,7 @@ Sachin Chitta Dave Coleman - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_planners/ompl/CHANGELOG.rst b/moveit_planners/ompl/CHANGELOG.rst index 06a4259f1c..37a663ac0b 100644 --- a/moveit_planners/ompl/CHANGELOG.rst +++ b/moveit_planners/ompl/CHANGELOG.rst @@ -117,7 +117,7 @@ Changelog for package moveit_planners_ompl * renamed newGoal to new_goal for keeping with formatting * setting GroupStateValidityCallbackFn member for constraint_sampler member and implementing callbacks for state validity checking * added functions to check validit of state, and also to act as callback for constraint sampler -* Added copy function from MoveIt! robot_state joint values to ompl state +* Added copy function from MoveIt robot_state joint values to ompl state * fix for demo constraints database linking error * Namespaced less useful debug output to allow to be easily silenced using ros console * Contributors: Dave Coleman, Dave Hershberger, Sachin Chitta, arjungm diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index ef25ce8452..317272df62 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -48,7 +48,7 @@ #include #include -/** \brief The MoveIt! interface to OMPL */ +/** \brief The MoveIt interface to OMPL */ namespace ompl_interface { /** @class OMPLInterface diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 3ef5246888..1bfa1379e6 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -241,10 +241,10 @@ class ModelBasedStateSpace : public ompl::base::StateSpace virtual void copyToOMPLState(ompl::base::State* state, const robot_state::RobotState& rstate) const; /** - * \brief Copy a single joint's values (which might have multiple variables) from a MoveIt! robot_state to an OMPL + * \brief Copy a single joint's values (which might have multiple variables) from a MoveIt robot_state to an OMPL * state. * \param state - output OMPL state with single joint modified - * \param robot_state - input MoveIt! state to get the joint value from + * \param robot_state - input MoveIt state to get the joint value from * \param joint_model - the joint to copy values of * \param ompl_state_joint_index - the index of the joint in the ompl state (passed in for efficiency, you should * cache this index) diff --git a/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp b/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp index 5d47880ea6..5deb25fce8 100644 --- a/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp +++ b/moveit_planners/ompl/ompl_interface/src/detail/state_validity_checker.cpp @@ -119,7 +119,7 @@ bool ompl_interface::StateValidityChecker::isValidWithoutCache(const ompl::base: return false; } - // convert ompl state to MoveIt! robot state + // convert ompl state to MoveIt robot state robot_state::RobotState* robot_state = tss_.getStateStorage(); planning_context_->getOMPLStateSpace()->copyToRobotState(*robot_state, state); diff --git a/moveit_planners/ompl/package.xml b/moveit_planners/ompl/package.xml index 1f2f7e6fc0..f7c87e00f2 100644 --- a/moveit_planners/ompl/package.xml +++ b/moveit_planners/ompl/package.xml @@ -1,12 +1,12 @@ moveit_planners_ompl 1.0.1 - MoveIt! interface to OMPL + MoveIt interface to OMPL Ioan Sucan Dave Coleman - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_plugins/README.md b/moveit_plugins/README.md index 62065de1f1..b6400b3a55 100644 --- a/moveit_plugins/README.md +++ b/moveit_plugins/README.md @@ -1,4 +1,4 @@ -# MoveIt! Plugins +# MoveIt Plugins This is a collection of plugins for MoveIt: - moveit_simple_controller_manager - A very basic controller manager plugin. Can connect to FollowJointTrajectoryAction and GripperCommandAction servers. diff --git a/moveit_plugins/moveit_fake_controller_manager/README.md b/moveit_plugins/moveit_fake_controller_manager/README.md index 102a296a23..cacbba6f9a 100644 --- a/moveit_plugins/moveit_fake_controller_manager/README.md +++ b/moveit_plugins/moveit_fake_controller_manager/README.md @@ -1,6 +1,6 @@ -# MoveIt! Fake Controller Manager +# MoveIt Fake Controller Manager -This package implements a series of fake trajectory controllers for MoveIt! -- to be used in simulation. +This package implements a series of fake trajectory controllers for MoveIt -- to be used in simulation. For example, the `demo.launch` generated by MoveIt's `setup_assistant`, employs fake controllers for nice visualization in `rviz`. For configuration, edit the file `config/fake_controllers.yaml`, and adjust the desired controller type. diff --git a/moveit_plugins/moveit_fake_controller_manager/package.xml b/moveit_plugins/moveit_fake_controller_manager/package.xml index 05c2662a48..d87a4a53bb 100644 --- a/moveit_plugins/moveit_fake_controller_manager/package.xml +++ b/moveit_plugins/moveit_fake_controller_manager/package.xml @@ -6,7 +6,7 @@ Ioan Sucan Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_plugins/moveit_plugins/package.xml b/moveit_plugins/moveit_plugins/package.xml index 265fa36725..c64dc69235 100644 --- a/moveit_plugins/moveit_plugins/package.xml +++ b/moveit_plugins/moveit_plugins/package.xml @@ -1,13 +1,13 @@ moveit_plugins 1.0.1 - Metapackage for MoveIt! plugins. + Metapackage for MoveIt plugins. Michael Ferguson Ioan Sucan Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_plugins/moveit_ros_control_interface/README.md b/moveit_plugins/moveit_ros_control_interface/README.md index d13be1b5a2..355006d366 100644 --- a/moveit_plugins/moveit_ros_control_interface/README.md +++ b/moveit_plugins/moveit_ros_control_interface/README.md @@ -1,4 +1,4 @@ -# MoveIt! ROS Control Plugin +# MoveIt ROS Control Plugin This package provides plugins of base class `moveit_controller_manager::MoveItControllerManager` and a new plugin base class for `moveit_controller_manager::MoveItControllerHandle` allocators. The allocator class is necessary because `moveit_controller_manager::MoveItControllerHandle` needs a name passed to the constructor. @@ -7,7 +7,7 @@ Two variantes are provided, `moveit_ros_control_interface::MoveItControllerManag ## moveit_ros_control_interface::MoveItControllerManager This plugin interfaces a single ros_control-driven node in the namespace given in the `~ros_control_namespace` ROS parameter. -It polls all controllers via the `list_controllers` service and passes their properties to MoveIt!. +It polls all controllers via the `list_controllers` service and passes their properties to MoveIt. The polling is throttled to 1 Hertz. ### Handle plugins @@ -17,7 +17,7 @@ These plugins should be registered with lookup names that match the correspondin Currently plugins for `position_controllers/JointTrajectoryController`, `velocity_controllers/JointTrajectoryController` and `effort_controllers/JointTrajectoryController` are available, which simply wrap `moveit_simple_controller_manager::FollowJointTrajectoryControllerHandle` instances. ### Setup -In your MoveIt! launch file (e.g. `ROBOT_moveit_config/launch/ROBOT_moveit_controller_manager.launch.xml`) set the `moveit_controller_manager` parameter: +In your MoveIt launch file (e.g. `ROBOT_moveit_config/launch/ROBOT_moveit_controller_manager.launch.xml`) set the `moveit_controller_manager` parameter: ``` ``` @@ -42,8 +42,8 @@ controller_list: ``` ### Controller switching -MoveIt! can decide which controllers have to be started and stopped. -Since only controller names with registered allocator plugins are handed over to MoveIt!, this implementation takes care of stopping other conflicting controllers based on their claimed resources and the resources for the to-be-started controllers. +MoveIt can decide which controllers have to be started and stopped. +Since only controller names with registered allocator plugins are handed over to MoveIt, this implementation takes care of stopping other conflicting controllers based on their claimed resources and the resources for the to-be-started controllers. ### Namespaces All controller names get prefixed by the namespace of the ros_control node. @@ -56,7 +56,7 @@ It spawns `moveit_ros_control_interface::MoveItControllerManager` instances with ### Setup -Just set the `moveit_controller_manager` parameter in your MoveIt! launch file (e.g. `ROBOT_moveit_config/launch/ROBOT_moveit_controller_manager.launch.xml`) +Just set the `moveit_controller_manager` parameter in your MoveIt launch file (e.g. `ROBOT_moveit_config/launch/ROBOT_moveit_controller_manager.launch.xml`) ``` ``` diff --git a/moveit_plugins/moveit_ros_control_interface/moveit_core_plugins.xml b/moveit_plugins/moveit_ros_control_interface/moveit_core_plugins.xml index f7461f59d5..3bd7e971cc 100644 --- a/moveit_plugins/moveit_ros_control_interface/moveit_core_plugins.xml +++ b/moveit_plugins/moveit_ros_control_interface/moveit_core_plugins.xml @@ -1,10 +1,10 @@ - ros_control controller manager interface for MoveIt! + ros_control controller manager interface for MoveIt - multiple ros_control controller managers interface for MoveIt! + multiple ros_control controller managers interface for MoveIt diff --git a/moveit_plugins/moveit_ros_control_interface/package.xml b/moveit_plugins/moveit_ros_control_interface/package.xml index 98d0206d4b..92bd877cdc 100644 --- a/moveit_plugins/moveit_ros_control_interface/package.xml +++ b/moveit_plugins/moveit_ros_control_interface/package.xml @@ -2,12 +2,12 @@ moveit_ros_control_interface 1.0.1 - ros_control controller manager interface for MoveIt! + ros_control controller manager interface for MoveIt Mathias Lüdtke Mathias Lüdtke - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index 8574dee376..e965d1b446 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -102,7 +102,7 @@ class GripperControllerHandle : public ActionBasedControllerHandleMichael Ferguson Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp index 2f15a4189a..e9921962db 100644 --- a/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp +++ b/moveit_plugins/moveit_simple_controller_manager/src/moveit_simple_controller_manager.cpp @@ -145,7 +145,7 @@ class MoveItSimpleControllerManager : public moveit_controller_manager::MoveItCo continue; } - /* add list of joints, used by controller manager and MoveIt! */ + /* add list of joints, used by controller manager and MoveIt */ for (int j = 0; j < controller_list[i]["joints"].size(); ++j) new_handle->addJoint(std::string(controller_list[i]["joints"][j])); diff --git a/moveit_ros/README.md b/moveit_ros/README.md index ba995b41ef..5755639551 100644 --- a/moveit_ros/README.md +++ b/moveit_ros/README.md @@ -1,6 +1,6 @@ -#MoveIt! ROS +#MoveIt ROS -This repository includes components of MoveIt! that use ROS. This is where much of the functionality MoveIt! provides is put together. Libraries from MoveIt! Core and various plugins are used to provide that functionality. +This repository includes components of MoveIt that use ROS. This is where much of the functionality MoveIt provides is put together. Libraries from MoveIt Core and various plugins are used to provide that functionality. - planning - planning interfaces - benchmarking diff --git a/moveit_ros/benchmarks/CHANGELOG.rst b/moveit_ros/benchmarks/CHANGELOG.rst index 98e4914f29..0bfdc8ef5a 100644 --- a/moveit_ros/benchmarks/CHANGELOG.rst +++ b/moveit_ros/benchmarks/CHANGELOG.rst @@ -155,13 +155,13 @@ Changelog for package moveit_ros_benchmarks as a symlink pointing to the versioned file. Because this sets each library's SONAME to the *full version*, this enforces that *every* binary links with the versioned library file from now on and - has to be relinked with *each* new release of MoveIt!. + has to be relinked with *each* new release of MoveIt. The alternative would be to set the SONAME to `$MAJOR.$MINOR` and ignore the patch version, but because we currently stay with one `$MAJOR.$MINOR` number within each ROS distribution, we had (and likely will have) ABI changes in the `$PATCH` version releases too. The reason for this commit is that it is practically impossible to maintain full ABI compatibility within each ROS distribution and still add the the features/patches the community asks for. - This has resulted in more than one ABI-incompatible MoveIt! release in the recent past + This has resulted in more than one ABI-incompatible MoveIt release in the recent past within a ROS distribution. Because the libraries have not been versioned up to now, there was no way to indicate the incompatible changes and users who did not rebuild their whole workspace with the new release encountered weird and hard-to-track segfaults diff --git a/moveit_ros/benchmarks/README.md b/moveit_ros/benchmarks/README.md index 775e391586..ada7c8a485 100644 --- a/moveit_ros/benchmarks/README.md +++ b/moveit_ros/benchmarks/README.md @@ -1,4 +1,4 @@ -# MoveIt! ROS Benchmarks +# MoveIt ROS Benchmarks This package provides methods to benchmark motion planning algorithms and aggregate/plot statistics. Results can be viewed in [Planner Arena](http://plannerarena.org/). diff --git a/moveit_ros/benchmarks/examples/demo1.yaml b/moveit_ros/benchmarks/examples/demo1.yaml index 92227c3814..b930a8187a 100644 --- a/moveit_ros/benchmarks/examples/demo1.yaml +++ b/moveit_ros/benchmarks/examples/demo1.yaml @@ -1,5 +1,5 @@ # This is an example configuration that loads the "Kitchen" scene from the -# local MoveIt! warehouse and benchmarks the "manipulator" group in the Pick1 +# local MoveIt warehouse and benchmarks the "manipulator" group in the Pick1 # query using the Start1 initial state (all pre-stored in the local warehouse) # Three different planners from OMPL are run a total of 50 times each, with a diff --git a/moveit_ros/benchmarks/examples/demo2.yaml b/moveit_ros/benchmarks/examples/demo2.yaml index 9151abf075..ba6048b01a 100644 --- a/moveit_ros/benchmarks/examples/demo2.yaml +++ b/moveit_ros/benchmarks/examples/demo2.yaml @@ -1,5 +1,5 @@ # This is an example configuration that loads the "Kitchen" scene from the -# local MoveIt! warehouse and benchmarks the "manipulator" group over all pairs +# local MoveIt warehouse and benchmarks the "manipulator" group over all pairs # of motion plan queries and start states in the Kitchen scene. # Five planners from two different plugins are run a total of 50 times each, with a diff --git a/moveit_ros/benchmarks/examples/demo_obstacles.yaml b/moveit_ros/benchmarks/examples/demo_obstacles.yaml index 70c7604e03..8616b78596 100644 --- a/moveit_ros/benchmarks/examples/demo_obstacles.yaml +++ b/moveit_ros/benchmarks/examples/demo_obstacles.yaml @@ -1,5 +1,5 @@ # This is an example configuration that loads the "Kitchen" scene from the -# local MoveIt! warehouse and benchmarks the "manipulator" group over all pairs +# local MoveIt warehouse and benchmarks the "manipulator" group over all pairs # of motion plan queries and start states in the Kitchen scene. # Five planners from two different plugins are run a total of 50 times each, with a diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml index 00ac5066e6..aaa20a017d 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml @@ -1,5 +1,5 @@ # This is an example configuration that loads the "Kitchen" scene from the -# local MoveIt! warehouse and benchmarks the "manipulator" group over all pairs +# local MoveIt warehouse and benchmarks the "manipulator" group over all pairs # of motion plan queries and start states in the Kitchen scene. # Five planners from two different plugins are run a total of 50 times each, with a diff --git a/moveit_ros/benchmarks/package.xml b/moveit_ros/benchmarks/package.xml index cbb64dbe81..acc1789072 100644 --- a/moveit_ros/benchmarks/package.xml +++ b/moveit_ros/benchmarks/package.xml @@ -2,12 +2,12 @@ moveit_ros_benchmarks 1.0.1 - Enhanced tools for benchmarks in MoveIt! + Enhanced tools for benchmarks in MoveIt Ryan Luna Dave Coleman - MoveIt! Release Team + MoveIt Release Team http://moveit.ros.org https://github.com/ros-planning/moveit/issues diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index ede31252e9..b48dd98a95 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -1063,7 +1063,7 @@ void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std: return; } - out << "MoveIt! version " << MOVEIT_VERSION << std::endl; + out << "MoveIt version " << MOVEIT_VERSION << std::endl; out << "Experiment " << brequest.name << std::endl; out << "Running on " << hostname << std::endl; out << "Starting at " << start_time << std::endl; diff --git a/moveit_ros/manipulation/package.xml b/moveit_ros/manipulation/package.xml index d8168e7329..6b1c82dddc 100644 --- a/moveit_ros/manipulation/package.xml +++ b/moveit_ros/manipulation/package.xml @@ -1,14 +1,14 @@ moveit_ros_manipulation 1.0.1 - Components of MoveIt! used for manipulation + Components of MoveIt used for manipulation Ioan Sucan Sachin Chitta Michael Görner Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/move_group/package.xml b/moveit_ros/move_group/package.xml index ffed75a12d..9c1130b9f1 100644 --- a/moveit_ros/move_group/package.xml +++ b/moveit_ros/move_group/package.xml @@ -7,7 +7,7 @@ Michael Ferguson Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/move_group/test/test_cancel_before_plan_execution.test b/moveit_ros/move_group/test/test_cancel_before_plan_execution.test index 51977ca919..edf4699d93 100644 --- a/moveit_ros/move_group/test/test_cancel_before_plan_execution.test +++ b/moveit_ros/move_group/test/test_cancel_before_plan_execution.test @@ -13,7 +13,7 @@ - + diff --git a/moveit_ros/moveit_ros/CHANGELOG.rst b/moveit_ros/moveit_ros/CHANGELOG.rst index d3a8959214..be0815f44c 100644 --- a/moveit_ros/moveit_ros/CHANGELOG.rst +++ b/moveit_ros/moveit_ros/CHANGELOG.rst @@ -30,7 +30,7 @@ Changelog for package moveit_ros 0.10.2 (2018-10-24) ------------------- -* Fix references to MoveIt! (`#1020 `_) +* Fix references to MoveIt (`#1020 `_) * Contributors: Mohmmad Ayman 0.10.1 (2018-05-25) diff --git a/moveit_ros/moveit_ros/package.xml b/moveit_ros/moveit_ros/package.xml index a64adef04d..60671d1f8f 100644 --- a/moveit_ros/moveit_ros/package.xml +++ b/moveit_ros/moveit_ros/package.xml @@ -1,7 +1,7 @@ moveit_ros 1.0.1 - Components of MoveIt! that use ROS + Components of MoveIt that use ROS Ioan Sucan Sachin Chitta Acorn Pooley @@ -9,7 +9,7 @@ Michael Ferguson Michael Görner Dave Coleman - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/occupancy_map_monitor/package.xml b/moveit_ros/occupancy_map_monitor/package.xml index 8c1e95689d..28c302748d 100644 --- a/moveit_ros/occupancy_map_monitor/package.xml +++ b/moveit_ros/occupancy_map_monitor/package.xml @@ -2,14 +2,14 @@ moveit_ros_occupancy_map_monitor 1.0.1 - Components of MoveIt! connecting to occupancy map + Components of MoveIt connecting to occupancy map Ioan Sucan Jon Binney Suat Gedikli Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/perception/package.xml b/moveit_ros/perception/package.xml index 61033ec542..0d3a038102 100644 --- a/moveit_ros/perception/package.xml +++ b/moveit_ros/perception/package.xml @@ -1,14 +1,14 @@ moveit_ros_perception 1.0.1 - Components of MoveIt! connecting to perception + Components of MoveIt connecting to perception Ioan Sucan Jon Binney Suat Gedikli Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/perception/semantic_world/src/semantic_world.cpp b/moveit_ros/perception/semantic_world/src/semantic_world.cpp index aa6d99403d..5407d287b7 100644 --- a/moveit_ros/perception/semantic_world/src/semantic_world.cpp +++ b/moveit_ros/perception/semantic_world/src/semantic_world.cpp @@ -38,7 +38,7 @@ #include #include -// MoveIt! +// MoveIt #include #include #include diff --git a/moveit_ros/planning/package.xml b/moveit_ros/planning/package.xml index ee9e4f923e..c5f426ebe1 100644 --- a/moveit_ros/planning/package.xml +++ b/moveit_ros/planning/package.xml @@ -2,13 +2,13 @@ moveit_ros_planning 1.0.1 - Planning components of MoveIt! that use ROS + Planning components of MoveIt that use ROS Ioan Sucan Sachin Chitta Michael Ferguson Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp b/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp index 6c62e6d411..8095e07b78 100644 --- a/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_with_sensing.cpp @@ -248,7 +248,7 @@ bool plan_execution::PlanWithSensing::lookAt(const std::set -// MoveIt! +// MoveIt #include static const std::string ROBOT_DESCRIPTION = "robot_description"; diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index eb655c1710..11a37c9329 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -34,7 +34,7 @@ /* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */ -// MoveIt! +// MoveIt #include #include diff --git a/moveit_ros/planning/trajectory_execution_manager/dox/trajectory_execution.dox b/moveit_ros/planning/trajectory_execution_manager/dox/trajectory_execution.dox index bb4b9068a4..ab7a5e683e 100644 --- a/moveit_ros/planning/trajectory_execution_manager/dox/trajectory_execution.dox +++ b/moveit_ros/planning/trajectory_execution_manager/dox/trajectory_execution.dox @@ -1,11 +1,11 @@ /** \page trajectory_execution Trajectory Execution Manager -@b MoveIt! includes a library for managing controllers and the execution of trajectories. This code exists in the trajectory_execution_manager namespace. +@b MoveIt includes a library for managing controllers and the execution of trajectories. This code exists in the trajectory_execution_manager namespace. The trajectory_execution_manager::TrajectoryExecutionManager class allows two main operations: - trajectory_execution_manager::TrajectoryExecutionManager::push() adds trajectories specified as a moveit_msgs::RobotTrajectory message type to a queue of trajectories to be executed in sequence. Each trajectory can be specified for any set of joints in the robot. Because controllers may only be available for certain groups of joints, this function may decide to split one trajectory into multiple ones and pass them to corresponding controllers (this time in parallel, using the same time stamp for the trajectory points). This approach assumes that controllers respect the time stamps specified for the waypoints. - trajectory_execution_manager::TrajectoryExecutionManager::execute() passes the appropriate trajectories to different controllers, monitors execution, optionally waits for completion of the execution and, very importantly, switches active controllers as needed (optionally) to be able to execute the specified trajectories. -The functionality of the trajectory execution in MoveIt! usually needs robot-specific interaction with controllers. For this reason, the concept of a controller manager specific to MoveIt! (moveit_controller_manager::MoveItControllerManager) was defined. This is an abstract class that defines the functionality needed by trajectory_execution_manager::TrajectoryExecutionManager and needs to be implemented for each robot type. Often, the implementation of these plugins are quite similar and it is easy to modify existing code to achieve the desired functionality (see for example pr2_moveit_controller_manager::Pr2MoveItControllerManager). +The functionality of the trajectory execution in MoveIt usually needs robot-specific interaction with controllers. For this reason, the concept of a controller manager specific to MoveIt (moveit_controller_manager::MoveItControllerManager) was defined. This is an abstract class that defines the functionality needed by trajectory_execution_manager::TrajectoryExecutionManager and needs to be implemented for each robot type. Often, the implementation of these plugins are quite similar and it is easy to modify existing code to achieve the desired functionality (see for example pr2_moveit_controller_manager::Pr2MoveItControllerManager). */ \ No newline at end of file diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 727b626fbe..1f919b0960 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -58,7 +58,7 @@ namespace moveit { -/** \brief Simple interface to MoveIt! components */ +/** \brief Simple interface to MoveIt components */ namespace planning_interface { class MoveItErrorCode : public moveit_msgs::MoveItErrorCodes diff --git a/moveit_ros/planning_interface/package.xml b/moveit_ros/planning_interface/package.xml index 3690783e3f..5c57d296b1 100644 --- a/moveit_ros/planning_interface/package.xml +++ b/moveit_ros/planning_interface/package.xml @@ -1,13 +1,13 @@ moveit_ros_planning_interface 1.0.1 - Components of MoveIt! that offer simpler interfaces to planning and execution + Components of MoveIt that offer simpler interfaces to planning and execution Ioan Sucan Michael Ferguson Michael Görner - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h index 3796d64760..e1e54a6bc9 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h +++ b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h @@ -42,7 +42,7 @@ namespace moveit { -/** \brief Tools for creating python bindings for MoveIt! */ +/** \brief Tools for creating python bindings for MoveIt */ namespace py_bindings_tools { /** \brief The constructor of this class ensures that ros::init() has diff --git a/moveit_ros/robot_interaction/CHANGELOG.rst b/moveit_ros/robot_interaction/CHANGELOG.rst index 93a596b313..9851f4f460 100644 --- a/moveit_ros/robot_interaction/CHANGELOG.rst +++ b/moveit_ros/robot_interaction/CHANGELOG.rst @@ -46,7 +46,7 @@ Changelog for package moveit_ros_robot_interaction 0.10.2 (2018-10-24) ------------------- -* [fix] Text refrences to MoveIt! (`#1020 `_) +* [fix] Text refrences to MoveIt (`#1020 `_) * Contributors: Mohmmad Ayman, Robert Haschke, mike lautman 0.10.1 (2018-05-25) diff --git a/moveit_ros/robot_interaction/package.xml b/moveit_ros/robot_interaction/package.xml index 25cc5b7107..83116910cf 100644 --- a/moveit_ros/robot_interaction/package.xml +++ b/moveit_ros/robot_interaction/package.xml @@ -1,13 +1,13 @@ moveit_ros_robot_interaction 1.0.1 - Components of MoveIt! that offer interaction via interactive markers + Components of MoveIt that offer interaction via interactive markers Ioan Sucan Michael Ferguson Robert Haschke - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp index f2773ed915..87c1321723 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_context.cpp @@ -81,7 +81,7 @@ void MotionPlanningFrame::planningAlgorithmIndexChanged(int index) void MotionPlanningFrame::resetDbButtonClicked() { - if (QMessageBox::warning(this, "Data about to be deleted", "The following dialog will allow you to drop a MoveIt! " + if (QMessageBox::warning(this, "Data about to be deleted", "The following dialog will allow you to drop a MoveIt " "Warehouse database. Are you sure you want to continue?", QMessageBox::Yes | QMessageBox::No) == QMessageBox::No) return; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui b/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui index b0debfae37..0f6825b916 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/ui/motion_planning_rviz_plugin_frame.ui @@ -11,7 +11,7 @@ - MoveIt! Planning Frame + MoveIt Planning Frame diff --git a/moveit_ros/visualization/package.xml b/moveit_ros/visualization/package.xml index 7b93f92cb1..a0f4183906 100644 --- a/moveit_ros/visualization/package.xml +++ b/moveit_ros/visualization/package.xml @@ -1,7 +1,7 @@ moveit_ros_visualization 1.0.1 - Components of MoveIt! that offer visualization + Components of MoveIt that offer visualization Ioan Sucan Dave Coleman @@ -9,7 +9,7 @@ Jon Binney Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/visualization/src/moveit_ros_visualization/moveitjoy_module.py b/moveit_ros/visualization/src/moveit_ros_visualization/moveitjoy_module.py index 0ad0a176d6..3868b0e3ad 100644 --- a/moveit_ros/visualization/src/moveit_ros_visualization/moveitjoy_module.py +++ b/moveit_ros/visualization/src/moveit_ros_visualization/moveitjoy_module.py @@ -35,7 +35,7 @@ # ********************************************************************/ # Author: Ryohei Ueda, Dave Coleman -# Desc: Interface between PS3/XBox controller and MoveIt! Motion Planning Rviz Plugin +# Desc: Interface between PS3/XBox controller and MoveIt Motion Planning Rviz Plugin from __future__ import print_function diff --git a/moveit_ros/warehouse/CHANGELOG.rst b/moveit_ros/warehouse/CHANGELOG.rst index e3d3c6dd37..ee636c4c9d 100644 --- a/moveit_ros/warehouse/CHANGELOG.rst +++ b/moveit_ros/warehouse/CHANGELOG.rst @@ -32,7 +32,7 @@ Changelog for package moveit_ros_warehouse 0.10.2 (2018-10-24) ------------------- -* [fix] Text refrences to MoveIt! (`#1020 `_) +* [fix] Text refrences to MoveIt (`#1020 `_) * [enhancement] warehouse: added params for timeout + #retries (`#1008 `_) * [maintenance] various compiler warnings (`#1038 `_) * Contributors: Mohmmad Ayman, Robert Haschke, dg-shadow, mike lautman diff --git a/moveit_ros/warehouse/package.xml b/moveit_ros/warehouse/package.xml index 976cdd1c79..14512ec42f 100644 --- a/moveit_ros/warehouse/package.xml +++ b/moveit_ros/warehouse/package.xml @@ -1,12 +1,12 @@ moveit_ros_warehouse 1.0.1 - Components of MoveIt! connecting to MongoDB + Components of MoveIt connecting to MongoDB Ioan Sucan Michael Ferguson - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp b/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp index 28cc32568f..595cae59c1 100644 --- a/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp +++ b/moveit_ros/warehouse/warehouse/src/initialize_demo_db.cpp @@ -132,7 +132,7 @@ int main(int argc, char** argv) cs.addConstraints(cmsg, psm.getRobotModel()->getName(), jmg->getName()); ROS_INFO("Added default constraint: '%s'", cmsg.name.c_str()); } - ROS_INFO("Default MoveIt! Warehouse was reset."); + ROS_INFO("Default MoveIt Warehouse was reset."); ros::shutdown(); diff --git a/moveit_runtime/package.xml b/moveit_runtime/package.xml index 8efd4a159f..f331186799 100644 --- a/moveit_runtime/package.xml +++ b/moveit_runtime/package.xml @@ -2,7 +2,7 @@ moveit_runtime 1.0.1 - moveit_runtime meta package contains MoveIt! packages that are essential for its runtime (e.g. running MoveIt! on robots). + moveit_runtime meta package contains MoveIt packages that are essential for its runtime (e.g. running MoveIt on robots). Isaac I. Y. Saito Isaac I. Y. Saito diff --git a/moveit_setup_assistant/CHANGELOG.rst b/moveit_setup_assistant/CHANGELOG.rst index a117cec6fa..dba4173b1f 100644 --- a/moveit_setup_assistant/CHANGELOG.rst +++ b/moveit_setup_assistant/CHANGELOG.rst @@ -51,7 +51,7 @@ Changelog for package moveit_setup_assistant * [capability][chomp] Failure recovery options for CHOMP by tweaking parameters (`#987 `_) * [capability] New screen for automatically generating interfaces to low level controllers(`#951 `_, `#994 `_, `#908 `_) * [capability] Perception screen for using laser scanner point clouds. (`#969 `_) -* [enhancement][GUI] Logo for MoveIt! 2.0, cleanup appearance (`#1059 `_) +* [enhancement][GUI] Logo for MoveIt 2.0, cleanup appearance (`#1059 `_) * [enhancement][GUI] added a setup assistant window icon (`#1028 `_) * [enhancement][GUI] Planning Groups screen (`#1017 `_) * [enhancement] use panda for test, and write test file in tmp dir (`#1042 `_) diff --git a/moveit_setup_assistant/README.md b/moveit_setup_assistant/README.md index 07feef853a..f346ead9ae 100644 --- a/moveit_setup_assistant/README.md +++ b/moveit_setup_assistant/README.md @@ -1 +1 @@ -# MoveIt! Setup Assistant +# MoveIt Setup Assistant diff --git a/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h b/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h index 788cfa0111..59b598bc45 100644 --- a/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h +++ b/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h @@ -175,7 +175,7 @@ class GenericParameter MOVEIT_CLASS_FORWARD(MoveItConfigData); /** \brief This class is shared with all widgets and contains the common configuration data - needed for generating each robot's MoveIt! configuration package. + needed for generating each robot's MoveIt configuration package. All SRDF data is contained in a subclass of this class - srdf_writer.cpp. This class also contains the functions for writing @@ -203,7 +203,7 @@ class MoveItConfigData }; unsigned long changes; // bitfield of changes (composed of InformationFields) - // All of the data needed for creating a MoveIt! Configuration Files + // All of the data needed for creating a MoveIt Configuration Files // ****************************************************************************************** // URDF Data @@ -411,7 +411,7 @@ class MoveItConfigData bool createFullSRDFPath(const std::string& package_path); /** - * Input .setup_assistant file - contains data used for the MoveIt! Setup Assistant + * Input .setup_assistant file - contains data used for the MoveIt Setup Assistant * * @param file_path path to .setup_assistant file * @return true if the file was read correctly diff --git a/moveit_setup_assistant/launch/setup_assistant.launch b/moveit_setup_assistant/launch/setup_assistant.launch index 4d908ba325..852c19c4ce 100644 --- a/moveit_setup_assistant/launch/setup_assistant.launch +++ b/moveit_setup_assistant/launch/setup_assistant.launch @@ -1,4 +1,4 @@ - + diff --git a/moveit_setup_assistant/package.xml b/moveit_setup_assistant/package.xml index 6db06b5a51..99c93b56e0 100644 --- a/moveit_setup_assistant/package.xml +++ b/moveit_setup_assistant/package.xml @@ -2,13 +2,13 @@ moveit_setup_assistant 1.0.1 - Generates a configuration package that makes it easy to use MoveIt! + Generates a configuration package that makes it easy to use MoveIt Dave Coleman Dave Coleman Robert Haschke - MoveIt! Release Team + MoveIt Release Team BSD diff --git a/moveit_setup_assistant/resources/source/MoveIt_Setup_Asst_Sm.xcf b/moveit_setup_assistant/resources/source/MoveIt_Setup_Asst_Sm.xcf index a3935559fdfbbb8d36e572704d1b2a534e02501e..a468ef57307a08794ec3366349620ec59989c688 100644 GIT binary patch delta 60 zcmbR8MQp+su? diff --git a/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test b/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test index f9c48abc8c..8845fd0815 100644 --- a/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test +++ b/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test @@ -10,7 +10,7 @@ These aren't suitable for actually jogging a robot in RViz, but they are good enough to test jog node output. --> - + @@ -19,20 +19,20 @@ - + - + - + - + - + diff --git a/moveit_experimental/kinematics_cache/CATKIN_IGNORE b/moveit_experimental/kinematics_cache/CATKIN_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/moveit_experimental/kinematics_constraint_aware/CATKIN_IGNORE b/moveit_experimental/kinematics_constraint_aware/CATKIN_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/moveit_experimental/package.xml b/moveit_experimental/package.xml deleted file mode 100644 index 222652ff6a..0000000000 --- a/moveit_experimental/package.xml +++ /dev/null @@ -1,26 +0,0 @@ - - moveit_experimental - 1.0.1 - Experimental packages for MoveIt - MoveIt Release Team - - BSD - http://moveit.ros.org - - catkin - - control_msgs - geometry_msgs - joy_teleop - moveit_ros_planning_interface - rosparam_shortcuts - spacenav_node - tf2_ros - - ros_pytest - rostest - - - - - From ae3d522ceb2059b9fd9163be3dbfba5f9a46003e Mon Sep 17 00:00:00 2001 From: Jonathan Binney Date: Tue, 13 Aug 2019 00:44:54 -0700 Subject: [PATCH 24/96] Switch from include guards to pragma once (#1615) --- .../moveit/background_processing/background_processing.h | 5 +---- moveit_core/backtrace/include/moveit/backtrace/backtrace.h | 5 +---- .../allvalid/collision_detector_allocator_allvalid.h | 5 +---- .../collision_detection/allvalid/collision_robot_allvalid.h | 5 +---- .../collision_detection/allvalid/collision_world_allvalid.h | 5 +---- .../include/moveit/collision_detection/collision_common.h | 5 +---- .../collision_detection/collision_detector_allocator.h | 5 +---- .../include/moveit/collision_detection/collision_matrix.h | 5 +---- .../moveit/collision_detection/collision_octomap_filter.h | 5 +---- .../include/moveit/collision_detection/collision_plugin.h | 5 +---- .../include/moveit/collision_detection/collision_robot.h | 5 +---- .../include/moveit/collision_detection/collision_tools.h | 5 +---- .../include/moveit/collision_detection/collision_world.h | 5 +---- .../include/moveit/collision_detection/world.h | 5 +---- .../include/moveit/collision_detection/world_diff.h | 5 +---- .../moveit/collision_detection_fcl/collision_common.h | 5 +---- .../collision_detector_allocator_fcl.h | 5 +---- .../collision_detector_fcl_plugin_loader.h | 4 +--- .../moveit/collision_detection_fcl/collision_robot_fcl.h | 5 +---- .../moveit/collision_detection_fcl/collision_world_fcl.h | 5 +---- .../include/moveit/collision_detection_fcl/fcl_compat.h | 4 +--- .../collision_common_distance_field.h | 4 +--- .../collision_detector_allocator_distance_field.h | 5 +---- .../collision_detector_allocator_hybrid.h | 5 +---- .../collision_distance_field_types.h | 5 +---- .../collision_robot_distance_field.h | 5 +---- .../moveit/collision_distance_field/collision_robot_hybrid.h | 5 +---- .../collision_world_distance_field.h | 5 +---- .../moveit/collision_distance_field/collision_world_hybrid.h | 5 +---- .../include/moveit/constraint_samplers/constraint_sampler.h | 5 +---- .../constraint_samplers/constraint_sampler_allocator.h | 5 +---- .../moveit/constraint_samplers/constraint_sampler_manager.h | 5 +---- .../moveit/constraint_samplers/constraint_sampler_tools.h | 5 +---- .../moveit/constraint_samplers/default_constraint_samplers.h | 5 +---- .../moveit/constraint_samplers/union_constraint_sampler.h | 5 +---- moveit_core/constraint_samplers/test/pr2_arm_ik.h | 4 +--- .../constraint_samplers/test/pr2_arm_kinematics_plugin.h | 5 +---- .../include/moveit/controller_manager/controller_manager.h | 5 +---- .../include/moveit/distance_field/distance_field.h | 5 +---- .../include/moveit/distance_field/find_internal_points.h | 5 +---- .../moveit/distance_field/propagation_distance_field.h | 5 +---- .../include/moveit/distance_field/voxel_grid.h | 4 +--- .../include/moveit/dynamics_solver/dynamics_solver.h | 4 +--- .../exceptions/include/moveit/exceptions/exceptions.h | 5 +---- .../moveit/kinematic_constraints/kinematic_constraint.h | 5 +---- .../include/moveit/kinematic_constraints/utils.h | 4 +--- .../include/moveit/kinematics_base/kinematics_base.h | 5 +---- .../include/moveit/kinematics_metrics/kinematics_metrics.h | 5 +---- moveit_core/macros/include/moveit/macros/class_forward.h | 5 +---- moveit_core/macros/include/moveit/macros/console_colors.h | 5 +---- moveit_core/macros/include/moveit/macros/declare_ptr.h | 5 +---- moveit_core/macros/include/moveit/macros/deprecation.h | 5 +---- .../include/moveit/planning_interface/planning_interface.h | 5 +---- .../include/moveit/planning_interface/planning_request.h | 5 +---- .../include/moveit/planning_interface/planning_response.h | 5 +---- .../planning_request_adapter/planning_request_adapter.h | 5 +---- .../include/moveit/planning_scene/planning_scene.h | 5 +---- moveit_core/profiler/include/moveit/profiler/profiler.h | 5 +---- moveit_core/robot_model/include/moveit/robot_model/aabb.h | 5 +---- .../include/moveit/robot_model/fixed_joint_model.h | 5 +---- .../include/moveit/robot_model/floating_joint_model.h | 5 +---- .../robot_model/include/moveit/robot_model/joint_model.h | 5 +---- .../include/moveit/robot_model/joint_model_group.h | 5 +---- .../robot_model/include/moveit/robot_model/link_model.h | 5 +---- .../include/moveit/robot_model/planar_joint_model.h | 5 +---- .../include/moveit/robot_model/prismatic_joint_model.h | 5 +---- .../include/moveit/robot_model/revolute_joint_model.h | 5 +---- .../robot_model/include/moveit/robot_model/robot_model.h | 5 +---- .../robot_state/include/moveit/robot_state/attached_body.h | 5 +---- .../include/moveit/robot_state/cartesian_interpolator.h | 5 +---- .../robot_state/include/moveit/robot_state/conversions.h | 5 +---- .../robot_state/include/moveit/robot_state/robot_state.h | 5 +---- .../include/moveit/robot_trajectory/robot_trajectory.h | 5 +---- .../include/moveit/sensor_manager/sensor_manager.h | 5 +---- .../iterative_spline_parameterization.h | 5 +---- .../trajectory_processing/iterative_time_parameterization.h | 5 +---- .../time_optimal_trajectory_generation.h | 5 +---- .../include/moveit/trajectory_processing/trajectory_tools.h | 5 +---- .../transforms/include/moveit/transforms/transforms.h | 5 +---- moveit_core/utils/include/moveit/utils/lexical_casts.h | 5 +---- .../utils/include/moveit/utils/robot_model_test_utils.h | 5 +---- .../collision_distance_field_ros_helpers.h | 4 +--- .../collision_robot_distance_field_ros.h | 5 +---- .../hybrid_collision_robot_ros.h | 5 +---- .../jog_arm/include/jog_arm/collision_check_thread.h | 5 +---- moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h | 4 +--- moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h | 5 +---- .../jog_arm/include/jog_arm/jog_ros_interface.h | 5 +---- .../jog_arm/include/jog_arm/low_pass_filter.h | 4 +--- .../include/kinematics_cache/kinematics_cache.h | 5 +---- .../include/kinematics_cache_ros/kinematics_cache_ros.h | 5 +---- .../include/moveit/kinematics_cache/kinematics_cache.h | 5 +---- .../kinematics_constraint_aware.h | 5 +---- .../kinematics_request_response.h | 5 +---- .../cached_ik_kinematics_plugin.h | 4 +--- .../cached_ik_kinematics_plugin/detail/GreedyKCenters.h | 5 +---- .../cached_ik_kinematics_plugin/detail/NearestNeighbors.h | 5 +---- .../detail/NearestNeighborsGNAT.h | 5 +---- .../kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp | 4 +--- .../include/moveit/kdl_kinematics_plugin/joint_mimic.hpp | 5 +---- .../moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h | 5 +---- .../moveit/lma_kinematics_plugin/lma_kinematics_plugin.h | 5 +---- .../moveit/srv_kinematics_plugin/srv_kinematics_plugin.h | 5 +---- .../include/chomp_interface/chomp_interface.h | 5 +---- .../include/chomp_interface/chomp_planning_context.h | 5 +---- .../include/chomp_motion_planner/chomp_cost.h | 5 +---- .../include/chomp_motion_planner/chomp_optimizer.h | 5 +---- .../include/chomp_motion_planner/chomp_parameters.h | 5 +---- .../include/chomp_motion_planner/chomp_planner.h | 5 +---- .../include/chomp_motion_planner/chomp_trajectory.h | 5 +---- .../include/chomp_motion_planner/chomp_utils.h | 5 +---- .../include/chomp_motion_planner/multivariate_gaussian.h | 5 +---- .../cpp/ompl_interface_ros/OMPLDynamicReconfigureConfig.h | 5 +---- .../include/moveit/ompl_interface/constraints_library.h | 5 +---- .../moveit/ompl_interface/detail/constrained_goal_sampler.h | 5 +---- .../moveit/ompl_interface/detail/constrained_sampler.h | 5 +---- .../ompl_interface/detail/constrained_valid_state_sampler.h | 5 +---- .../moveit/ompl_interface/detail/constraint_approximations.h | 5 +---- .../moveit/ompl_interface/detail/projection_evaluators.h | 5 +---- .../moveit/ompl_interface/detail/state_validity_checker.h | 5 +---- .../moveit/ompl_interface/detail/threadsafe_state_storage.h | 4 +--- .../moveit/ompl_interface/model_based_planning_context.h | 5 +---- .../include/moveit/ompl_interface/ompl_interface.h | 5 +---- .../parameterization/joint_space/joint_model_state_space.h | 5 +---- .../joint_space/joint_model_state_space_factory.h | 5 +---- .../parameterization/model_based_state_space.h | 5 +---- .../parameterization/model_based_state_space_factory.h | 5 +---- .../parameterization/work_space/pose_model_state_space.h | 5 +---- .../work_space/pose_model_state_space_factory.h | 5 +---- .../include/moveit/ompl_interface/planning_context_manager.h | 5 +---- .../sbpl_interface/include/sbpl_interface/bfs3d/BFS_3D.h | 5 +---- .../core/sbpl_interface/include/sbpl_interface/bresenham.h | 5 +---- .../include/sbpl_interface/dummy_environment.h | 5 +---- .../include/sbpl_interface/environment_chain3d.h | 5 +---- .../include/sbpl_interface/environment_chain3d_types.h | 5 +---- .../sbpl_interface/include/sbpl_interface/sbpl_interface.h | 5 +---- .../include/sbpl_interface/sbpl_meta_interface.h | 5 +---- .../core/sbpl_interface/include/sbpl_interface/sbpl_params.h | 5 +---- .../include/moveit_ros_control_interface/ControllerHandle.h | 5 +---- .../action_based_controller_handle.h | 5 +---- .../follow_joint_trajectory_controller_handle.h | 5 +---- .../gripper_controller_handle.h | 5 +---- .../benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h | 5 +---- .../benchmarks/include/moveit/benchmarks/BenchmarkOptions.h | 5 +---- .../move_group_pick_place_capability/capability_names.h | 5 +---- .../src/pick_place_action_capability.h | 5 +---- .../include/moveit/pick_place/approach_and_translate_stage.h | 5 +---- .../include/moveit/pick_place/manipulation_pipeline.h | 5 +---- .../pick_place/include/moveit/pick_place/manipulation_plan.h | 5 +---- .../include/moveit/pick_place/manipulation_stage.h | 5 +---- .../pick_place/include/moveit/pick_place/pick_place.h | 5 +---- .../pick_place/include/moveit/pick_place/pick_place_params.h | 5 +---- .../pick_place/include/moveit/pick_place/plan_stage.h | 5 +---- .../include/moveit/pick_place/reachable_valid_pose_filter.h | 5 +---- .../move_group/include/moveit/move_group/capability_names.h | 5 +---- .../include/moveit/move_group/move_group_capability.h | 5 +---- .../include/moveit/move_group/move_group_context.h | 5 +---- moveit_ros/move_group/include/moveit/move_group/node_name.h | 5 +---- .../apply_planning_scene_service_capability.h | 5 +---- .../default_capabilities/cartesian_path_service_capability.h | 5 +---- .../default_capabilities/clear_octomap_service_capability.h | 5 +---- .../execute_trajectory_action_capability.h | 5 +---- .../get_planning_scene_service_capability.h | 5 +---- .../src/default_capabilities/kinematics_service_capability.h | 5 +---- .../src/default_capabilities/move_action_capability.h | 5 +---- .../src/default_capabilities/plan_service_capability.h | 5 +---- .../default_capabilities/query_planners_service_capability.h | 5 +---- .../state_validation_service_capability.h | 5 +---- .../include/moveit/occupancy_map_monitor/occupancy_map.h | 5 +---- .../moveit/occupancy_map_monitor/occupancy_map_monitor.h | 5 +---- .../moveit/occupancy_map_monitor/occupancy_map_updater.h | 5 +---- .../depth_image_octomap_updater.h | 5 +---- .../moveit/lazy_free_space_updater/lazy_free_space_updater.h | 5 +---- .../include/moveit/mesh_filter/depth_self_filter_nodelet.h | 5 +---- .../mesh_filter/include/moveit/mesh_filter/filter_job.h | 4 +--- .../mesh_filter/include/moveit/mesh_filter/gl_mesh.h | 4 +--- .../mesh_filter/include/moveit/mesh_filter/gl_renderer.h | 4 +--- .../mesh_filter/include/moveit/mesh_filter/mesh_filter.h | 4 +--- .../include/moveit/mesh_filter/mesh_filter_base.h | 5 +---- .../mesh_filter/include/moveit/mesh_filter/sensor_model.h | 5 +---- .../include/moveit/mesh_filter/stereo_camera_model.h | 4 +--- .../include/moveit/mesh_filter/transform_provider.h | 4 +--- .../include/moveit/point_containment_filter/shape_mask.h | 5 +---- .../pointcloud_octomap_updater/pointcloud_octomap_updater.h | 5 +---- .../include/moveit/semantic_world/semantic_world.h | 5 +---- .../moveit/collision_plugin_loader/collision_plugin_loader.h | 5 +---- .../constraint_sampler_manager_loader.h | 5 +---- .../kinematics_plugin_loader/kinematics_plugin_loader.h | 5 +---- .../include/moveit/plan_execution/plan_execution.h | 4 +--- .../include/moveit/plan_execution/plan_representation.h | 4 +--- .../include/moveit/plan_execution/plan_with_sensing.h | 4 +--- .../include/moveit/planning_pipeline/planning_pipeline.h | 5 +---- .../moveit/planning_scene_monitor/current_state_monitor.h | 5 +---- .../moveit/planning_scene_monitor/planning_scene_monitor.h | 5 +---- .../moveit/planning_scene_monitor/trajectory_monitor.h | 5 +---- .../rdf_loader/include/moveit/rdf_loader/rdf_loader.h | 4 +--- .../include/moveit/robot_model_loader/robot_model_loader.h | 4 +--- .../trajectory_execution_manager.h | 5 +---- .../test/test_moveit_controller_manager.h | 4 +--- .../common_planning_interface_objects/common_objects.h | 5 +---- .../moveit/move_group_interface/move_group_interface.h | 5 +---- .../planning_scene_interface/planning_scene_interface.h | 5 +---- .../include/moveit/py_bindings_tools/py_conversions.h | 5 +---- .../include/moveit/py_bindings_tools/roscpp_initializer.h | 5 +---- .../include/moveit/py_bindings_tools/serialize_msg.h | 5 +---- .../include/moveit/robot_interaction/interaction.h | 5 +---- .../include/moveit/robot_interaction/interaction_handler.h | 5 +---- .../moveit/robot_interaction/interactive_marker_helpers.h | 5 +---- .../include/moveit/robot_interaction/kinematic_options.h | 5 +---- .../include/moveit/robot_interaction/kinematic_options_map.h | 5 +---- .../include/moveit/robot_interaction/locked_robot_state.h | 5 +---- .../include/moveit/robot_interaction/robot_interaction.h | 5 +---- .../motion_planning_rviz_plugin/motion_planning_display.h | 5 +---- .../motion_planning_rviz_plugin/motion_planning_frame.h | 5 +---- .../motion_planning_param_widget.h | 5 +---- .../planning_scene_rviz_plugin/planning_scene_display.h | 5 +---- .../moveit/robot_state_rviz_plugin/robot_state_display.h | 5 +---- .../include/moveit/rviz_plugin_render_tools/octomap_render.h | 4 +--- .../moveit/rviz_plugin_render_tools/planning_link_updater.h | 5 +---- .../moveit/rviz_plugin_render_tools/planning_scene_render.h | 5 +---- .../include/moveit/rviz_plugin_render_tools/render_shapes.h | 5 +---- .../rviz_plugin_render_tools/robot_state_visualization.h | 5 +---- .../moveit/rviz_plugin_render_tools/trajectory_panel.h | 5 +---- .../rviz_plugin_render_tools/trajectory_visualization.h | 5 +---- .../moveit/trajectory_rviz_plugin/trajectory_display.h | 5 +---- .../warehouse/include/moveit/warehouse/constraints_storage.h | 5 +---- .../include/moveit/warehouse/moveit_message_storage.h | 5 +---- .../include/moveit/warehouse/planning_scene_storage.h | 5 +---- .../include/moveit/warehouse/planning_scene_world_storage.h | 5 +---- .../warehouse/include/moveit/warehouse/state_storage.h | 5 +---- .../moveit/warehouse/trajectory_constraints_storage.h | 5 +---- .../warehouse/include/moveit/warehouse/warehouse_connector.h | 5 +---- .../setup_assistant/tools/compute_default_collisions.h | 5 +---- .../moveit/setup_assistant/tools/moveit_config_data.h | 5 +---- moveit_setup_assistant/src/tools/collision_linear_model.h | 5 +---- moveit_setup_assistant/src/tools/collision_matrix_model.h | 5 +---- moveit_setup_assistant/src/tools/rotated_header_view.h | 5 +---- .../src/widgets/author_information_widget.h | 5 +---- .../src/widgets/configuration_files_widget.h | 5 +---- moveit_setup_assistant/src/widgets/controller_edit_widget.h | 5 +---- .../src/widgets/default_collisions_widget.h | 5 +---- moveit_setup_assistant/src/widgets/double_list_widget.h | 5 +---- moveit_setup_assistant/src/widgets/end_effectors_widget.h | 5 +---- moveit_setup_assistant/src/widgets/group_edit_widget.h | 5 +---- moveit_setup_assistant/src/widgets/header_widget.h | 5 +---- moveit_setup_assistant/src/widgets/kinematic_chain_widget.h | 5 +---- moveit_setup_assistant/src/widgets/navigation_widget.h | 5 +---- moveit_setup_assistant/src/widgets/passive_joints_widget.h | 5 +---- moveit_setup_assistant/src/widgets/perception_widget.h | 5 +---- moveit_setup_assistant/src/widgets/planning_groups_widget.h | 5 +---- moveit_setup_assistant/src/widgets/robot_poses_widget.h | 5 +---- moveit_setup_assistant/src/widgets/ros_controllers_widget.h | 5 +---- moveit_setup_assistant/src/widgets/setup_assistant_widget.h | 5 +---- moveit_setup_assistant/src/widgets/setup_screen_widget.h | 5 +---- moveit_setup_assistant/src/widgets/simulation_widget.h | 5 +---- moveit_setup_assistant/src/widgets/start_screen_widget.h | 5 +---- moveit_setup_assistant/src/widgets/virtual_joints_widget.h | 5 +---- 257 files changed, 257 insertions(+), 1002 deletions(-) diff --git a/moveit_core/background_processing/include/moveit/background_processing/background_processing.h b/moveit_core/background_processing/include/moveit/background_processing/background_processing.h index 270be22622..b87a82f997 100644 --- a/moveit_core/background_processing/include/moveit/background_processing/background_processing.h +++ b/moveit_core/background_processing/include/moveit/background_processing/background_processing.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_BACKGROUND_PROCESSING_ -#define MOVEIT_BACKGROUND_PROCESSING_ +#pragma once #include #include @@ -113,5 +112,3 @@ class BackgroundProcessing : private boost::noncopyable }; } } - -#endif diff --git a/moveit_core/backtrace/include/moveit/backtrace/backtrace.h b/moveit_core/backtrace/include/moveit/backtrace/backtrace.h index c00033f9bc..224c0fe2dc 100644 --- a/moveit_core/backtrace/include/moveit/backtrace/backtrace.h +++ b/moveit_core/backtrace/include/moveit/backtrace/backtrace.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_BACKTRACE_ -#define MOVEIT_BACKTRACE_ +#pragma once #include @@ -63,5 +62,3 @@ void get_backtrace(std::ostream& out) } #endif } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 549a6d6990..0382b492d7 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_ALL_VALID_H_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_ALL_VALID_H_ +#pragma once #include #include @@ -52,5 +51,3 @@ class CollisionDetectorAllocatorAllValid static const std::string NAME; // defined in collision_world_allvalid.cpp }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h index 9ac86aa6bb..9ce0e2dc15 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_ROBOT_ALLVALID_ -#define MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_ROBOT_ALLVALID_ +#pragma once #include @@ -84,5 +83,3 @@ class CollisionRobotAllValid : public CollisionRobot const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const override; }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h index c950579668..dcf045b554 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_WORLD_ALLVALID_ -#define MOVEIT_COLLISION_DETECTION_ALLVALID_COLLISION_WORLD_ALLVALID_ +#pragma once #include @@ -75,5 +74,3 @@ class CollisionWorldAllValid : public CollisionWorld void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const override; }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index 601755b0bb..c4ec8f25a5 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_COMMON_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_COMMON_ +#pragma once #include #include @@ -382,5 +381,3 @@ struct DistanceResult } }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index aed7eac019..018d6be5e0 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_ +#pragma once #include #include @@ -108,5 +107,3 @@ class CollisionDetectorAllocatorTemplate : public CollisionDetectorAllocator } }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h index 59eb26e535..1b9e36e36e 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_MATRIX_ +#pragma once #include #include @@ -278,5 +277,3 @@ class AllowedCollisionMatrix std::map default_allowed_contacts_; }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 466d58a685..1460b80ff0 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -34,8 +34,7 @@ /* Author: Adam Leeper */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_OCTOMAP_FILTER_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_OCTOMAP_FILTER_ +#pragma once #include #include @@ -62,5 +61,3 @@ int refineContactNormals(const World::ObjectConstPtr& object, CollisionResult& r double cell_bbx_search_distance = 1.0, double allowed_angle_divergence = 0.0, bool estimate_depth = false, double iso_value = 0.5, double metaball_radius_multiple = 1.5); } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 156318f4bc..5142e41bb9 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_PLUGIN_H -#define MOVEIT_COLLISION_DETECTION_COLLISION_PLUGIN_H +#pragma once #include #include @@ -94,5 +93,3 @@ class CollisionPlugin }; } // namespace collision_detection - -#endif // MOVEIT_COLLISION_DETECTION_COLLISION_PLUGIN_H diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h index 1b6d476a89..2249b56c73 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_ROBOT_ +#pragma once #include #include @@ -309,5 +308,3 @@ class CollisionRobot std::map link_scale_; }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h index 6893c41444..8b06686148 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_tools.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_TOOLS_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_TOOLS_ +#pragma once #include #include @@ -72,5 +71,3 @@ bool getSensorPositioning(geometry_msgs::Point& point, const std::set @@ -278,5 +277,3 @@ class CollisionWorld : private boost::noncopyable WorldConstPtr world_const_; // always same as world_ }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index f461043f4a..82b299673e 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Acorn Pooley, Sachin Chitta */ -#ifndef MOVEIT_COLLISION_DETECTION_WORLD_ -#define MOVEIT_COLLISION_DETECTION_WORLD_ +#pragma once #include @@ -300,5 +299,3 @@ class World std::vector observers_; }; } - -#endif diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h index 5f2013d7f0..84ae6a522c 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world_diff.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_COLLISION_DETECTION_WORLD_DIFF_ -#define MOVEIT_COLLISION_DETECTION_WORLD_DIFF_ +#pragma once #include #include @@ -126,5 +125,3 @@ class WorldDiff WorldWeakPtr world_; }; } - -#endif diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index f9fce66b21..347a9426d1 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_COMMON_ -#define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_COMMON_ +#pragma once #include #include @@ -298,5 +297,3 @@ inline void fcl2costsource(const fcl::CostSourced& fcs, CostSource& cs) cs.cost = fcs.cost_density; } } - -#endif diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index 6b7ec1ce52..a72b4fd5d6 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_FCL_H_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_FCL_H_ +#pragma once #include #include @@ -51,5 +50,3 @@ class CollisionDetectorAllocatorFCL static const std::string NAME; // defined in collision_world_fcl.cpp }; } - -#endif diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h index 18d7e8c40f..e1d749474c 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_fcl_plugin_loader.h @@ -2,8 +2,7 @@ * collision_detector_fcl_plugin_loader.h */ -#ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_DETECTOR_FCL_PLUGIN_LOADER_H_ -#define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_DETECTOR_FCL_PLUGIN_LOADER_H_ +#pragma once #include #include @@ -16,4 +15,3 @@ class CollisionDetectorFCLPluginLoader : public CollisionPlugin virtual bool initialize(const planning_scene::PlanningScenePtr& scene, bool exclusive) const; }; } -#endif // MOVEIT_COLLISION_DETECTION_FCL_COLLISION_DETECTOR_FCL_PLUGIN_LOADER_H_ \ No newline at end of file diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h index a46794e999..917658bab3 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ -#define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ +#pragma once #include @@ -96,5 +95,3 @@ class CollisionRobotFCL : public CollisionRobot std::vector fcl_objs_; }; } - -#endif diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h index e6d9557630..65cc476471 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_WORLD_FCL_ -#define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_WORLD_FCL_ +#pragma once #include #include @@ -97,5 +96,3 @@ class CollisionWorldFCL : public CollisionWorld World::ObserverHandle observer_handle_; }; } - -#endif diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h index 9eeda077cd..123fac3c08 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/fcl_compat.h @@ -34,8 +34,7 @@ /* Author: Benjamin Scholz */ -#ifndef MOVEIT_COLLISION_DETECTION_FCL_COMPAT_ -#define MOVEIT_COLLISION_DETECTION_FCL_COMPAT_ +#pragma once #include @@ -98,4 +97,3 @@ class DynamicAABBTreeCollisionManager; using DynamicAABBTreeCollisionManagerd = fcl::DynamicAABBTreeCollisionManager; } #endif -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index fa5910a581..024be61cfe 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_ -#define MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_ +#pragma once #include #include @@ -180,4 +179,3 @@ PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const rob void getBodySphereVisualizationMarkers(const GroupStateRepresentationPtr& gsr, const std::string& reference_frame, visualization_msgs::MarkerArray& body_marker_array); } -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 53c71b9f35..9581cefa7b 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_DISTANCE_FIELD_H_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_DISTANCE_FIELD_H_ +#pragma once #include #include @@ -52,5 +51,3 @@ class CollisionDetectorAllocatorDistanceField static const std::string NAME; // defined in collision_world_distance_field.cpp }; } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index 6eb3277ee7..a2c643b282 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_HYBRID_H_ -#define MOVEIT_COLLISION_DETECTION_COLLISION_DETECTOR_HYBRID_H_ +#pragma once #include #include @@ -52,5 +51,3 @@ class CollisionDetectorAllocatorHybrid static const std::string NAME; // defined in collision_world_hybrid.cpp }; } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h index 364386fb34..9816e4be1e 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_distance_field_types.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_DISTANCE_FIELD_TYPES_ -#define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_DISTANCE_FIELD_TYPES_ +#pragma once #include #include @@ -524,5 +523,3 @@ void getCollisionMarkers(const std::string& frame_id, const std::string& ns, con const std::vector& posed_vector_decompositions, const std::vector& gradients, visualization_msgs::MarkerArray& arr); } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h index 2c968dac76..dd13b12043 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_DISTANCE_FIELD_ -#define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_DISTANCE_FIELD_ +#pragma once #include #include @@ -263,5 +262,3 @@ class CollisionRobotDistanceField : public CollisionRobot planning_scene::PlanningScenePtr planning_scene_; }; } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h index 528fe3b226..7b188ce97e 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_ -#define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_ROBOT_HYBRID_H_ +#pragma once #include #include @@ -97,5 +96,3 @@ class CollisionRobotHybrid : public collision_detection::CollisionRobotFCL CollisionRobotDistanceFieldPtr crobot_distance_; }; } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h index d2a5e950fb..ff05802ab9 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_DISTANCE_FIELD_ -#define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_DISTANCE_FIELD_ +#pragma once #include #include @@ -199,5 +198,3 @@ class CollisionWorldDistanceField : public CollisionWorld World::ObserverHandle observer_handle_; }; } - -#endif diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h index 9b70e3c6dc..bb3d07e8cf 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_HYBRID_H_ -#define MOVEIT_COLLISION_DISTANCE_FIELD_COLLISION_WORLD_HYBRID_H_ +#pragma once #include #include @@ -115,5 +114,3 @@ class CollisionWorldHybrid : public CollisionWorldFCL CollisionWorldDistanceFieldPtr cworld_distance_; }; } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h index ce2f2ed073..f86cc069fa 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ -#define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ +#pragma once #include #include @@ -296,5 +295,3 @@ class ConstraintSampler bool verbose_; ///< True if verbosity is on }; } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h index abc68a0e28..89db5e830e 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_allocator.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ALLOCATOR_ -#define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_ALLOCATOR_ +#pragma once #include #include @@ -62,5 +61,3 @@ class ConstraintSamplerAllocator const moveit_msgs::Constraints& constr) const = 0; }; } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h index 05c88548e8..630e307c97 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_MANAGER_ -#define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_MANAGER_ +#pragma once #include #include @@ -144,5 +143,3 @@ class ConstraintSamplerManager sampler_alloc_; /**< \brief Holds the constraint sampler allocators, which will be tested in order */ }; } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h index ce405b9d51..f222aea111 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/constraint_sampler_tools.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_TOOLS_ -#define MOVEIT_CONSTRAINT_SAMPLERS_CONSTRAINT_SAMPLER_TOOLS_ +#pragma once #include #include @@ -55,5 +54,3 @@ double countSamplesPerSecond(const ConstraintSamplerPtr& sampler, const robot_st double countSamplesPerSecond(const moveit_msgs::Constraints& constr, const planning_scene::PlanningSceneConstPtr& scene, const std::string& group); } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h index 77a048bdb8..399e3cc7ef 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/default_constraint_samplers.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_CONSTRAINT_SAMPLERS_ -#define MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_CONSTRAINT_SAMPLERS_ +#pragma once #include #include @@ -526,5 +525,3 @@ class IKConstraintSampler : public ConstraintSampler Eigen::Isometry3d eef_to_ik_tip_transform_; /**< \brief Holds the transformation from end effector to IK tip frame */ }; } - -#endif diff --git a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h index a50c16298a..7b00590491 100644 --- a/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h +++ b/moveit_core/constraint_samplers/include/moveit/constraint_samplers/union_constraint_sampler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_UNION_CONSTRAINT_SAMPLER_ -#define MOVEIT_CONSTRAINT_SAMPLERS_DEFAULT_UNION_CONSTRAINT_SAMPLER_ +#pragma once #include @@ -169,5 +168,3 @@ class UnionConstraintSampler : public ConstraintSampler std::vector samplers_; /**< \brief Holder for sorted internal list of samplers*/ }; } - -#endif diff --git a/moveit_core/constraint_samplers/test/pr2_arm_ik.h b/moveit_core/constraint_samplers/test/pr2_arm_ik.h index 8ba4052ca9..46d4a7ef32 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_ik.h +++ b/moveit_core/constraint_samplers/test/pr2_arm_ik.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef PR2_ARM_IK_H -#define PR2_ARM_IK_H +#pragma once #include #include @@ -190,4 +189,3 @@ class PR2ArmIK std::vector continuous_joint_; }; } -#endif // PR2_ARM_IK_H diff --git a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h index 94bd16926e..a3cca94e0c 100644 --- a/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h +++ b/moveit_core/constraint_samplers/test/pr2_arm_kinematics_plugin.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef PR2_ARM_IK_NODE_H -#define PR2_ARM_IK_NODE_H +#pragma once #include #include @@ -261,5 +260,3 @@ class PR2ArmKinematicsPlugin : public kinematics::KinematicsBase moveit_msgs::MoveItErrorCodes& error_code) const; }; } - -#endif diff --git a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h index 2a32ff04a8..7af922b3bc 100644 --- a/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h +++ b/moveit_core/controller_manager/include/moveit/controller_manager/controller_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_CONTROLLER_MANAGER_ -#define MOVEIT_MOVEIT_CONTROLLER_MANAGER_ +#pragma once #include #include @@ -209,5 +208,3 @@ class MoveItControllerManager const std::vector& deactivate) = 0; }; } - -#endif diff --git a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h index d1164a4935..b4bfa238d7 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/distance_field.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson, E. Gil Jones */ -#ifndef MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H -#define MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H +#pragma once #include #include @@ -627,5 +626,3 @@ class DistanceField }; } // namespace distance_field - -#endif // MOVEIT_DISTANCE_FIELD_DISTANCE_FIELD_H diff --git a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h index be419651f9..27363466e1 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h +++ b/moveit_core/distance_field/include/moveit/distance_field/find_internal_points.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley */ -#ifndef MOVEIT_DISTANCE_FIELD__FIND_INTERNAL_POINTS_ -#define MOVEIT_DISTANCE_FIELD__FIND_INTERNAL_POINTS_ +#pragma once #include #include @@ -54,5 +53,3 @@ namespace distance_field */ void findInternalPointsConvex(const bodies::Body& body, double resolution, EigenSTL::vector_Vector3d& points); } - -#endif diff --git a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h index 66cbf2daa2..a278a7f6d6 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h +++ b/moveit_core/distance_field/include/moveit/distance_field/propagation_distance_field.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan, Ken Anderson */ -#ifndef MOVEIT_DISTANCE_FIELD_PROPAGATION_DISTANCE_FIELD_ -#define MOVEIT_DISTANCE_FIELD_PROPAGATION_DISTANCE_FIELD_ +#pragma once #include #include @@ -611,5 +610,3 @@ inline double PropagationDistanceField::getDistance(const PropDistanceFieldVoxel return sqrt_table_[object.distance_square_] - sqrt_table_[object.negative_distance_square_]; } } - -#endif diff --git a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h index f85cfbdcd7..6cecf4e050 100644 --- a/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h +++ b/moveit_core/distance_field/include/moveit/distance_field/voxel_grid.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan, Acorn Pooley */ -#ifndef MOVEIT_DISTANCE_FIELD_VOXEL_GRID_ -#define MOVEIT_DISTANCE_FIELD_VOXEL_GRID_ +#pragma once #include #include @@ -579,4 +578,3 @@ inline bool VoxelGrid::worldToGrid(const Eigen::Vector3d& world, Eigen::Vecto } } // namespace distance_field -#endif diff --git a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h index 3e73f8b036..1f579d0c6f 100644 --- a/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h +++ b/moveit_core/dynamics_solver/include/moveit/dynamics_solver/dynamics_solver.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef MOVEIT_DYNAMICS_SOLVER_DYNAMICS_SOLVER_ -#define MOVEIT_DYNAMICS_SOLVER_DYNAMICS_SOLVER_ +#pragma once // KDL #include @@ -151,4 +150,3 @@ class DynamicsSolver double gravity_; // Norm of the gravity vector passed in initialize() }; } -#endif diff --git a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h index 7918eef07d..34394e987c 100644 --- a/moveit_core/exceptions/include/moveit/exceptions/exceptions.h +++ b/moveit_core/exceptions/include/moveit/exceptions/exceptions.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley, Ioan Sucan */ -#ifndef MOVEIT_EXCEPTIONS_ -#define MOVEIT_EXCEPTIONS_ +#pragma once #include @@ -56,5 +55,3 @@ class Exception : public std::runtime_error explicit Exception(const std::string& what_arg); }; } - -#endif diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 936ebf82fe..4d15e35d63 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_KINEMATIC_CONSTRAINTS_KINEMATIC_CONSTRAINT_ -#define MOVEIT_KINEMATIC_CONSTRAINTS_KINEMATIC_CONSTRAINT_ +#pragma once #include #include @@ -1069,5 +1068,3 @@ class KinematicConstraintSet moveit_msgs::Constraints all_constraints_; /**< \brief Messages corresponding to all internal constraints */ }; } - -#endif diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index e5e9e5f74f..f2dfe6f84a 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_KINEMATIC_CONSTRAINTS_UTILS_ -#define MOVEIT_KINEMATIC_CONSTRAINTS_UTILS_ +#pragma once #include #include @@ -216,4 +215,3 @@ bool constructConstraints(XmlRpc::XmlRpcValue& params, moveit_msgs::Constraints& */ bool resolveConstraintFrames(const robot_state::RobotState& state, moveit_msgs::Constraints& constraints); } -#endif diff --git a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h index a3323e95ae..59fc3ee7c4 100644 --- a/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h +++ b/moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta, Dave Coleman */ -#ifndef MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_ -#define MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_ +#pragma once #include #include @@ -665,5 +664,3 @@ class KinematicsBase std::string removeSlash(const std::string& str) const; }; }; - -#endif diff --git a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h index c92a7d5063..da5c213e49 100644 --- a/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h +++ b/moveit_core/kinematics_metrics/include/moveit/kinematics_metrics/kinematics_metrics.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_ -#define MOVEIT_KINEMATICS_METRICS_KINEMATICS_METRICS_ +#pragma once #include #include @@ -158,5 +157,3 @@ class KinematicsMetrics double penalty_multiplier_; }; } - -#endif diff --git a/moveit_core/macros/include/moveit/macros/class_forward.h b/moveit_core/macros/include/moveit/macros/class_forward.h index 57bb5ce56b..1c5ab03544 100644 --- a/moveit_core/macros/include/moveit/macros/class_forward.h +++ b/moveit_core/macros/include/moveit/macros/class_forward.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MACROS_CLASS_FORWARD_ -#define MOVEIT_MACROS_CLASS_FORWARD_ +#pragma once #include @@ -58,5 +57,3 @@ #define MOVEIT_STRUCT_FORWARD(C) \ struct C; \ MOVEIT_DECLARE_PTR(C, C); - -#endif diff --git a/moveit_core/macros/include/moveit/macros/console_colors.h b/moveit_core/macros/include/moveit/macros/console_colors.h index 4ea7b65d39..0da6ae80de 100644 --- a/moveit_core/macros/include/moveit/macros/console_colors.h +++ b/moveit_core/macros/include/moveit/macros/console_colors.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSOLE_COLORS_ -#define MOVEIT_CONSOLE_COLORS_ +#pragma once #define MOVEIT_CONSOLE_COLOR_RESET "\033[0m" #define MOVEIT_CONSOLE_COLOR_GRAY "\033[90m" @@ -46,5 +45,3 @@ #define MOVEIT_CONSOLE_COLOR_BLUE "\033[94m" #define MOVEIT_CONSOLE_COLOR_PURPLE "\033[95m" #define MOVEIT_CONSOLE_COLOR_CYAN "\033[96m" - -#endif diff --git a/moveit_core/macros/include/moveit/macros/declare_ptr.h b/moveit_core/macros/include/moveit/macros/declare_ptr.h index 36506e618a..fc3eeb6e39 100644 --- a/moveit_core/macros/include/moveit/macros/declare_ptr.h +++ b/moveit_core/macros/include/moveit/macros/declare_ptr.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_MACROS_DECLARE_PTR_ -#define MOVEIT_MACROS_DECLARE_PTR_ +#pragma once #include @@ -70,5 +69,3 @@ typedef std::shared_ptr ConstPtr; \ typedef std::weak_ptr WeakPtr; \ typedef std::weak_ptr ConstWeakPtr; - -#endif diff --git a/moveit_core/macros/include/moveit/macros/deprecation.h b/moveit_core/macros/include/moveit/macros/deprecation.h index 1a69e998f0..20f24b06ac 100644 --- a/moveit_core/macros/include/moveit/macros/deprecation.h +++ b/moveit_core/macros/include/moveit/macros/deprecation.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_MACROS_DEPRECATION_ -#define MOVEIT_MACROS_DEPRECATION_ +#pragma once /** \def MOVEIT_DEPRECATED Macro that marks functions as deprecated */ @@ -47,5 +46,3 @@ #else #define MOVEIT_DEPRECATED /* Nothing */ #endif - -#endif diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h index 93748f43ef..9cf2f206f4 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_interface.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_INTERFACE_ -#define MOVEIT_PLANNING_INTERFACE_PLANNING_INTERFACE_ +#pragma once #include #include @@ -213,5 +212,3 @@ class PlannerManager }; } // planning_interface - -#endif diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h index 6138283043..a738f0a0df 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_request.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_REQUEST_ -#define MOVEIT_PLANNING_INTERFACE_PLANNING_REQUEST_ +#pragma once #include @@ -46,5 +45,3 @@ namespace planning_interface typedef moveit_msgs::MotionPlanRequest MotionPlanRequest; } // planning_interface - -#endif diff --git a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h index c902ffd741..e05209921d 100644 --- a/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h +++ b/moveit_core/planning_interface/include/moveit/planning_interface/planning_response.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_RESPONSE_ -#define MOVEIT_PLANNING_INTERFACE_PLANNING_RESPONSE_ +#pragma once #include #include @@ -68,5 +67,3 @@ struct MotionPlanDetailedResponse }; } // planning_interface - -#endif diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index e950bfba11..fd2b34a424 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_REQUEST_ADAPTER_PLANNING_REQUEST_ADAPTER_ -#define MOVEIT_PLANNING_REQUEST_ADAPTER_PLANNING_REQUEST_ADAPTER_ +#pragma once #include #include @@ -134,5 +133,3 @@ class PlanningRequestAdapterChain std::vector adapters_; }; } - -#endif diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 6503f7793a..32adb11f61 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Acorn Pooley */ -#ifndef MOVEIT_PLANNING_SCENE_PLANNING_SCENE_ -#define MOVEIT_PLANNING_SCENE_PLANNING_SCENE_ +#pragma once #include #include @@ -1056,5 +1055,3 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from std::unique_ptr object_types_; }; } - -#endif diff --git a/moveit_core/profiler/include/moveit/profiler/profiler.h b/moveit_core/profiler/include/moveit/profiler/profiler.h index b996af16f7..554ec2b755 100644 --- a/moveit_core/profiler/include/moveit/profiler/profiler.h +++ b/moveit_core/profiler/include/moveit/profiler/profiler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PROFILER_ -#define MOVEIT_PROFILER_ +#pragma once #define MOVEIT_ENABLE_PROFILING 1 @@ -448,5 +447,3 @@ class Profiler } #endif - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/aabb.h b/moveit_core/robot_model/include/moveit/robot_model/aabb.h index 2ed8ebf382..5c1b84df13 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/aabb.h +++ b/moveit_core/robot_model/include/moveit/robot_model/aabb.h @@ -34,8 +34,7 @@ /* Author: Martin Pecka */ -#ifndef MOVEIT_ROBOT_MODEL_AABB_H -#define MOVEIT_ROBOT_MODEL_AABB_H +#pragma once #include @@ -52,5 +51,3 @@ class AABB : public Eigen::AlignedBox3d }; } } - -#endif // MOVEIT_ROBOT_MODEL_AABB_H diff --git a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h index 265b13576c..d10b1622a7 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/fixed_joint_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_FIXED_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_FIXED_JOINT_MODEL_ +#pragma once #include @@ -68,5 +67,3 @@ class FixedJointModel : public JointModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h index a39a8471e5..6d721d9bf5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/floating_joint_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_FLOATING_JOINT_MODEL_ +#pragma once #include @@ -91,5 +90,3 @@ class FloatingJointModel : public JointModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h index 982ae78bb8..aa07321d73 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_ +#pragma once #include #include @@ -521,5 +520,3 @@ class JointModel std::ostream& operator<<(std::ostream& out, const VariableBounds& b); } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h index d46e1fc748..108e1a5ab3 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h +++ b/moveit_core/robot_model/include/moveit/robot_model/joint_model_group.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_GROUP_ -#define MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_GROUP_ +#pragma once #include #include @@ -745,5 +744,3 @@ class JointModelGroup }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/link_model.h b/moveit_core/robot_model/include/moveit/robot_model/link_model.h index decebc2a82..d586dfded0 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/link_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/link_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_LINK_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_LINK_MODEL_ +#pragma once #include #include @@ -283,5 +282,3 @@ class LinkModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h index 0900e0b8d9..3524250e41 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/planar_joint_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_PLANAR_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_PLANAR_JOINT_MODEL_ +#pragma once #include @@ -86,5 +85,3 @@ class PlanarJointModel : public JointModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h index f745947e18..87678c55a5 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/prismatic_joint_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_PRISMATIC_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_PRISMATIC_JOINT_MODEL_ +#pragma once #include @@ -86,5 +85,3 @@ class PrismaticJointModel : public JointModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h index 33adc02839..76322c2b04 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/revolute_joint_model.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_REVOLUTE_JOINT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_REVOLUTE_JOINT_MODEL_ +#pragma once #include @@ -97,5 +96,3 @@ class RevoluteJointModel : public JointModel }; } } - -#endif diff --git a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h index 5e0b98061d..835c675c04 100644 --- a/moveit_core/robot_model/include/moveit/robot_model/robot_model.h +++ b/moveit_core/robot_model/include/moveit/robot_model/robot_model.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_MODEL_ -#define MOVEIT_CORE_ROBOT_MODEL_ +#pragma once #include #include @@ -621,5 +620,3 @@ class RobotModel namespace robot_model = moveit::core; namespace robot_state = moveit::core; - -#endif diff --git a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h index 3453d3233d..bf5a4f5ec6 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/attached_body.h +++ b/moveit_core/robot_state/include/moveit/robot_state/attached_body.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_ROBOT_STATE_ATTACHED_BODY_ -#define MOVEIT_ROBOT_STATE_ATTACHED_BODY_ +#pragma once #include #include @@ -184,5 +183,3 @@ class AttachedBody }; } } - -#endif diff --git a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h index a5447f2f85..ecf843c99a 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h +++ b/moveit_core/robot_state/include/moveit/robot_state/cartesian_interpolator.h @@ -36,8 +36,7 @@ /* Author: Ioan Sucan, Mike Lautman */ -#ifndef MOVEIT_CORE_ROBOT_STATE_CARTESIAN_INTERPOLATOR_ -#define MOVEIT_CORE_ROBOT_STATE_CARTESIAN_INTERPOLATOR_ +#pragma once #include @@ -215,5 +214,3 @@ class CartesianInterpolator } // end of namespace core } // end of namespace moveit - -#endif diff --git a/moveit_core/robot_state/include/moveit/robot_state/conversions.h b/moveit_core/robot_state/include/moveit/robot_state/conversions.h index 655329acff..e5d1017d33 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/conversions.h +++ b/moveit_core/robot_state/include/moveit/robot_state/conversions.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Dave Coleman */ -#ifndef MOVEIT_ROBOT_STATE_CONVERSIONS_ -#define MOVEIT_ROBOT_STATE_CONVERSIONS_ +#pragma once #include #include @@ -143,5 +142,3 @@ void robotStateToStream(const RobotState& state, std::ostream& out, void streamToRobotState(RobotState& state, const std::string& line, const std::string& separator = ","); } } - -#endif diff --git a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h index c65a5e7eeb..126b20baf9 100644 --- a/moveit_core/robot_state/include/moveit/robot_state/robot_state.h +++ b/moveit_core/robot_state/include/moveit/robot_state/robot_state.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CORE_ROBOT_STATE_ -#define MOVEIT_CORE_ROBOT_STATE_ +#pragma once #include #include @@ -1837,5 +1836,3 @@ as the new values that correspond to the group */ std::ostream& operator<<(std::ostream& out, const RobotState& s); } } - -#endif diff --git a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h index 7b3a4b9507..1601cd4279 100644 --- a/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h +++ b/moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Adam Leeper */ -#ifndef MOVEIT_ROBOT_TRAJECTORY_KINEMATIC_TRAJECTORY_ -#define MOVEIT_ROBOT_TRAJECTORY_KINEMATIC_TRAJECTORY_ +#pragma once #include #include @@ -265,5 +264,3 @@ class RobotTrajectory std::deque duration_from_previous_; }; } - -#endif diff --git a/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h b/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h index a8f1a1615b..222e703504 100644 --- a/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h +++ b/moveit_core/sensor_manager/include/moveit/sensor_manager/sensor_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_SENSOR_MANAGER_ -#define MOVEIT_MOVEIT_SENSOR_MANAGER_ +#pragma once #include #include @@ -103,5 +102,3 @@ class MoveItSensorManager moveit_msgs::RobotTrajectory& sensor_trajectory) = 0; }; } - -#endif diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_spline_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_spline_parameterization.h index c3cb24cb12..67f4683047 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_spline_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_spline_parameterization.h @@ -35,8 +35,7 @@ /* Author: Ken Anderson */ -#ifndef MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_SPLINE_PARAMETERIZATION__ -#define MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_SPLINE_PARAMETERIZATION__ +#pragma once #include #include @@ -85,5 +84,3 @@ class IterativeSplineParameterization /// If false, move the 2nd and 2nd-last points. }; } - -#endif diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_time_parameterization.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_time_parameterization.h index 59b883f089..64e3d2b5b9 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_time_parameterization.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/iterative_time_parameterization.h @@ -34,8 +34,7 @@ /* Author: Ken Anderson */ -#ifndef MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_PARABOLIC_SMOOTHER_ -#define MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_PARABOLIC_SMOOTHER_ +#pragma once #include #include @@ -69,5 +68,3 @@ class IterativeParabolicTimeParameterization double findT2(const double d1, const double d2, const double t1, double t2, const double a_max) const; }; } - -#endif diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h index 21db426fd1..3e8268a92c 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/time_optimal_trajectory_generation.h @@ -36,8 +36,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef MOVEIT_TRAJECTORY_PROCESSING_TIME_OPTIMAL_TRAJECTORY_GENERATION_H -#define MOVEIT_TRAJECTORY_PROCESSING_TIME_OPTIMAL_TRAJECTORY_GENERATION_H +#pragma once #include #include @@ -174,5 +173,3 @@ class TimeOptimalTrajectoryGeneration const double resample_dt_; }; } // namespace trajectory_processing - -#endif // MOVEIT_TRAJECTORY_PROCESSING_TIME_OPTIMAL_TRAJECTORY_GENERATION_H diff --git a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h index 0c7658d39f..4c818af3e8 100644 --- a/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h +++ b/moveit_core/trajectory_processing/include/moveit/trajectory_processing/trajectory_tools.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_TRAJECTORY_PROCESSING_TRAJECTORY_TOOLS_ -#define MOVEIT_TRAJECTORY_PROCESSING_TRAJECTORY_TOOLS_ +#pragma once #include @@ -44,5 +43,3 @@ namespace trajectory_processing bool isTrajectoryEmpty(const moveit_msgs::RobotTrajectory& trajectory); std::size_t trajectoryWaypointCount(const moveit_msgs::RobotTrajectory& trajectory); } - -#endif diff --git a/moveit_core/transforms/include/moveit/transforms/transforms.h b/moveit_core/transforms/include/moveit/transforms/transforms.h index 949a61341f..6833b606aa 100644 --- a/moveit_core/transforms/include/moveit/transforms/transforms.h +++ b/moveit_core/transforms/include/moveit/transforms/transforms.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_TRANSFORMS_ -#define MOVEIT_TRANSFORMS_ +#pragma once #include #include @@ -200,5 +199,3 @@ class Transforms : private boost::noncopyable }; } } - -#endif diff --git a/moveit_core/utils/include/moveit/utils/lexical_casts.h b/moveit_core/utils/include/moveit/utils/lexical_casts.h index ce0fbcb5b5..3dc0e84ab8 100644 --- a/moveit_core/utils/include/moveit/utils/lexical_casts.h +++ b/moveit_core/utils/include/moveit/utils/lexical_casts.h @@ -34,8 +34,7 @@ /* Author: Simon Schmeisser */ -#ifndef MOVEIT_CORE_UTILS_LEXICAL_CASTS_ -#define MOVEIT_CORE_UTILS_LEXICAL_CASTS_ +#pragma once /** \file lexical_casts.h * \brief locale-agnostic conversion functions from floating point numbers to strings @@ -68,5 +67,3 @@ double toDouble(const std::string& s); float toFloat(const std::string& s); } } - -#endif diff --git a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h index 079cf49749..652d7111b6 100644 --- a/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h +++ b/moveit_core/utils/include/moveit/utils/robot_model_test_utils.h @@ -35,8 +35,7 @@ /* Author: Bryce Willey */ /** \brief convenience functions and classes used for making simple robot models for testing. */ -#ifndef MOVEIT_CORE_UTILS_TEST_ -#define MOVEIT_CORE_UTILS_TEST_ +#pragma once #include #include @@ -196,5 +195,3 @@ class RobotModelBuilder }; } } - -#endif diff --git a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_distance_field_ros_helpers.h b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_distance_field_ros_helpers.h index c90f312dc6..0495d74d2a 100644 --- a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_distance_field_ros_helpers.h +++ b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_distance_field_ros_helpers.h @@ -34,8 +34,7 @@ /** \author E. Gil Jones */ -#ifndef COLLISION_DISTANCE_FIELD_HELPERS_H_ -#define COLLISION_DISTANCE_FIELD_HELPERS_H_ +#pragma once #include #include @@ -126,4 +125,3 @@ static inline bool loadLinkBodySphereDecompositions( return true; } } -#endif diff --git a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_robot_distance_field_ros.h b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_robot_distance_field_ros.h index 8c9861b953..1fb7a58e56 100644 --- a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_robot_distance_field_ros.h +++ b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/collision_robot_distance_field_ros.h @@ -34,8 +34,7 @@ /** \author E. Gil Jones */ -#ifndef _COLLISION_ROBOT_DISTANCE_FIELD_ROS_H_ -#define _COLLISION_ROBOT_DISTANCE_FIELD_ROS_H_ +#pragma once #include #include @@ -63,5 +62,3 @@ class CollisionRobotDistanceFieldROS : public CollisionRobotDistanceField } }; } - -#endif diff --git a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/hybrid_collision_robot_ros.h b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/hybrid_collision_robot_ros.h index 193d9debd2..8cb1c75f98 100644 --- a/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/hybrid_collision_robot_ros.h +++ b/moveit_experimental/collision_distance_field_ros/include/collision_distance_field_ros/hybrid_collision_robot_ros.h @@ -34,8 +34,7 @@ /** \author E. Gil Jones */ -#ifndef _COLLISION_ROBOT_HYBRID_ROS_H_ -#define _COLLISION_ROBOT_HYBRID_ROS_H_ +#pragma once #include #include @@ -63,5 +62,3 @@ class CollisionRobotHybridROS : public CollisionRobotHybrid } }; } - -#endif diff --git a/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h b/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h index 1049f26967..4b3680b5f3 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h +++ b/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h @@ -37,8 +37,7 @@ // /////////////////////////////////////////////////////////////////////////////// -#ifndef JOG_ARM_COLLISION_CHECK_THREAD_H -#define JOG_ARM_COLLISION_CHECK_THREAD_H +#pragma once #include #include @@ -54,5 +53,3 @@ class CollisionCheckThread pthread_mutex_t& mutex, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr); }; } - -#endif // JOG_ARM_COLLISION_CHECK_THREAD_H diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h b/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h index fa2129c8dc..cc8309dd62 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h @@ -37,8 +37,7 @@ // /////////////////////////////////////////////////////////////////////////////// -#ifndef JOG_ARM_JOG_ARM_DATA_H -#define JOG_ARM_JOG_ARM_DATA_H +#pragma once #include #include @@ -93,4 +92,3 @@ struct JogArmParameters bool use_gazebo, check_collisions, publish_joint_positions, publish_joint_velocities, publish_joint_accelerations; }; } -#endif // JOG_ARM_DATA_H diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h index ff278e76fe..f9ba6da0c9 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h @@ -37,8 +37,7 @@ // /////////////////////////////////////////////////////////////////////////////// -#ifndef JOG_ARM_JOG_CALCS_H -#define JOG_ARM_JOG_CALCS_H +#pragma once #include #include @@ -135,5 +134,3 @@ class JogCalcs uint num_joints_; }; } // namespace jog_arm - -#endif // JOG_ARM_JOG_CALCS_H diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h b/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h index 636e920afe..ef5f7d8d66 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h @@ -39,8 +39,7 @@ // Server node for arm jogging with MoveIt. -#ifndef JOG_ARM_JOG_ROS_INTERFACE_H -#define JOG_ARM_JOG_ROS_INTERFACE_H +#pragma once #include #include @@ -87,5 +86,3 @@ class JogROSInterface JogArmParameters ros_parameters_; }; } // namespace jog_arm - -#endif // JOG_ARM_JOG_ROS_INTERFACE_H diff --git a/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h b/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h index d6b4402072..d1a3e937db 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h +++ b/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h @@ -37,8 +37,7 @@ // /////////////////////////////////////////////////////////////////////////////// -#ifndef JOG_ARM_LOW_PASS_FILTER_H -#define JOG_ARM_LOW_PASS_FILTER_H +#pragma once namespace jog_arm { @@ -64,4 +63,3 @@ class LowPassFilter double filter_coeff_ = 10.; }; } // namespace jog_arm -#endif // JOG_ARM_LOW_PASS_FILTER_H diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h index 1d9f7fd217..952965a57e 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache/include/kinematics_cache/kinematics_cache.h @@ -35,8 +35,7 @@ * Author: Sachin Chitta *********************************************************************/ -#ifndef KINEMATICS_CACHE_H_ -#define KINEMATICS_CACHE_H_ +#pragma once #include #include @@ -184,5 +183,3 @@ class KinematicsCache typedef std::shared_ptr KinematicsCachePtr; } - -#endif diff --git a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/include/kinematics_cache_ros/kinematics_cache_ros.h b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/include/kinematics_cache_ros/kinematics_cache_ros.h index ceaa9f86e6..187c133f40 100644 --- a/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/include/kinematics_cache_ros/kinematics_cache_ros.h +++ b/moveit_experimental/kinematics_cache/v1/kinematics_cache_ros/include/kinematics_cache_ros/kinematics_cache_ros.h @@ -35,8 +35,7 @@ * Author: Sachin Chitta *********************************************************************/ -#ifndef KINEMATICS_CACHE_ROS_H_ -#define KINEMATICS_CACHE_ROS_H_ +#pragma once #include #include @@ -70,5 +69,3 @@ class KinematicsCacheROS : public kinematics_cache::KinematicsCache planning_models::RobotModelPtr kinematic_model_; /** A kinematics model */ }; } - -#endif diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h index 0a7c793614..233ad5f27c 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/include/moveit/kinematics_cache/kinematics_cache.h @@ -35,8 +35,7 @@ * Author: Sachin Chitta *********************************************************************/ -#ifndef KINEMATICS_CACHE_H_ -#define KINEMATICS_CACHE_H_ +#pragma once #include #include @@ -182,5 +181,3 @@ class KinematicsCache typedef std::shared_ptr KinematicsCachePtr; } - -#endif diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h index 2ec2f70299..4200f2761e 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_constraint_aware.h @@ -35,8 +35,7 @@ * Author: Sachin Chitta *********************************************************************/ -#ifndef MOVEIT_KINEMATICS_CONSTRAINT_AWARE_ -#define MOVEIT_KINEMATICS_CONSTRAINT_AWARE_ +#pragma once // System #include @@ -141,5 +140,3 @@ class KinematicsConstraintAware unsigned int ik_attempts_; }; } - -#endif diff --git a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h index 6d2086a08a..b54fd335e3 100644 --- a/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h +++ b/moveit_experimental/kinematics_constraint_aware/include/moveit/kinematics_constraint_aware/kinematics_request_response.h @@ -35,8 +35,7 @@ * Author: Sachin Chitta *********************************************************************/ -#ifndef MOVEIT_KINEMATICS_CONSTRAINT_AWARE_KINEMATICS_REQUEST_RESPONSE_ -#define MOVEIT_KINEMATICS_CONSTRAINT_AWARE_KINEMATICS_REQUEST_RESPONSE_ +#pragma once // System #include @@ -105,5 +104,3 @@ class KinematicsResponse bool result_; }; } - -#endif diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h index 649d89f7df..1d4a76286f 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/cached_ik_kinematics_plugin.h @@ -34,8 +34,7 @@ /* Author: Mark Moll */ -#ifndef MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_PLUGIN_ -#define MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_PLUGIN_ +#pragma once #include #include @@ -348,4 +347,3 @@ class CachedMultiTipIKKinematicsPlugin : public CachedIKKinematicsPlugin -#ifndef MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_GREEDY_K_CENTERS_ -#define MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_GREEDY_K_CENTERS_ +#pragma once #include #include @@ -129,5 +128,3 @@ class GreedyKCenters std::mt19937 generator_{ std::random_device{}() }; }; } - -#endif diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h index dc026872fe..e3fc410078 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighbors.h @@ -36,8 +36,7 @@ // This file is a slightly modified version of -#ifndef MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_NEAREST_NEIGHBORS_ -#define MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_NEAREST_NEIGHBORS_ +#pragma once #include #include @@ -116,5 +115,3 @@ class NearestNeighbors DistanceFunction distFun_; }; } - -#endif diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h index 6d3b72f55e..dc21099fc6 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h +++ b/moveit_kinematics/cached_ik_kinematics_plugin/include/moveit/cached_ik_kinematics_plugin/detail/NearestNeighborsGNAT.h @@ -36,8 +36,7 @@ // This file is a slightly modified version of -#ifndef MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_NEAREST_NEIGHBORS_GNAT_ -#define MOVEIT_ROS_PLANNING_CACHED_IK_KINEMATICS_NEAREST_NEIGHBORS_GNAT_ +#pragma once #include "NearestNeighbors.h" #include "GreedyKCenters.h" @@ -720,5 +719,3 @@ class NearestNeighborsGNAT : public NearestNeighbors<_T> std::unordered_set removed_; }; } - -#endif diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp index 9cff711601..afefc41f3c 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/chainiksolver_vel_mimic_svd.hpp @@ -23,8 +23,7 @@ // linear relationship to that of another joint. // Copyright (C) 2013 Sachin Chitta, Willow Garage -#ifndef KDL_CHAIN_IKSOLVERVEL_PINV_Mimic_HPP -#define KDL_CHAIN_IKSOLVERVEL_PINV_Mimic_HPP +#pragma once #include #include @@ -116,4 +115,3 @@ class ChainIkSolverVelMimicSVD : public ChainIkSolverVel Jacobian jac_reduced_; // reduced Jacobian with contributions of mimic joints mapped onto active DoFs }; } -#endif diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.hpp b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.hpp index 6814441850..45ad0a0c47 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.hpp +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/joint_mimic.hpp @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef MOVEIT_KDL_KINEMATICS_PLUGIN_JOINT_MIMIC -#define MOVEIT_KDL_KINEMATICS_PLUGIN_JOINT_MIMIC +#pragma once namespace kdl_kinematics_plugin { @@ -71,5 +70,3 @@ class JointMimic } }; } - -#endif diff --git a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h index 9c4a150045..6e13e834f4 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h +++ b/moveit_kinematics/kdl_kinematics_plugin/include/moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta, David Lu!!, Ugo Cupcic */ -#ifndef MOVEIT_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_ -#define MOVEIT_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_ +#pragma once // ROS #include @@ -196,5 +195,3 @@ class KDLKinematicsPlugin : public kinematics::KinematicsBase double orientation_vs_position_weight_; }; } - -#endif diff --git a/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h b/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h index 0ec6c0667d..79c1155d67 100644 --- a/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h +++ b/moveit_kinematics/lma_kinematics_plugin/include/moveit/lma_kinematics_plugin/lma_kinematics_plugin.h @@ -34,8 +34,7 @@ /* Author: Francisco Suarez-Ruiz */ -#ifndef MOVEIT_ROS_PLANNING_LMA_KINEMATICS_PLUGIN_H -#define MOVEIT_ROS_PLANNING_LMA_KINEMATICS_PLUGIN_H +#pragma once // ROS #include @@ -182,5 +181,3 @@ class LMAKinematicsPlugin : public kinematics::KinematicsBase double orientation_vs_position_weight_; }; } - -#endif diff --git a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h index 50449662fe..f0a1494648 100644 --- a/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h +++ b/moveit_kinematics/srv_kinematics_plugin/include/moveit/srv_kinematics_plugin/srv_kinematics_plugin.h @@ -39,8 +39,7 @@ \todo: better support for redundant joints */ -#ifndef MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_ -#define MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_ +#pragma once // ROS #include @@ -159,5 +158,3 @@ class SrvKinematicsPlugin : public kinematics::KinematicsBase std::shared_ptr ik_service_client_; }; } - -#endif diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h index 1272a130cc..464da4ab92 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_interface.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef CHOMP_INTERFACE_CHOMP_INTERFACE_H -#define CHOMP_INTERFACE_CHOMP_INTERFACE_H +#pragma once #include #include @@ -64,5 +63,3 @@ class CHOMPInterface : public chomp::ChompPlanner chomp::ChompParameters params_; }; } - -#endif diff --git a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h index 69169f8a66..2dee290b9b 100644 --- a/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h +++ b/moveit_planners/chomp/chomp_interface/include/chomp_interface/chomp_planning_context.h @@ -34,8 +34,7 @@ /* Author: Chittaranjan Srinivas Swaminathan */ -#ifndef CHOMP_INTERFACE_CHOMP_PLANNING_CONTEXT_H -#define CHOMP_INTERFACE_CHOMP_PLANNING_CONTEXT_H +#pragma once #include #include @@ -65,5 +64,3 @@ class CHOMPPlanningContext : public planning_interface::PlanningContext }; } /* namespace chomp_interface */ - -#endif /* CHOMP_PLANNING_CONTEXT_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h index bda7cbd3f9..a60b1e1c71 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_cost.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef CHOMP_COST_H_ -#define CHOMP_COST_H_ +#pragma once #include #include @@ -97,5 +96,3 @@ inline double ChompCost::getCost(Eigen::MatrixXd::ColXpr joint_trajectory) const } } // namespace chomp - -#endif /* CHOMP_COST_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index fba516334b..f98009e133 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef CHOMP_OPTIMIZER_H_ -#define CHOMP_OPTIMIZER_H_ +#pragma once #include #include @@ -224,5 +223,3 @@ class ChompOptimizer bool isCurrentTrajectoryMeshToMeshCollisionFree() const; }; } - -#endif /* CHOMP_OPTIMIZER_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h index f1446c9d8a..ab78f274ca 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_parameters.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef CHOMP_PARAMETERS_H_ -#define CHOMP_PARAMETERS_H_ +#pragma once #include @@ -98,5 +97,3 @@ class ChompParameters }; } // namespace chomp - -#endif /* CHOMP_PARAMETERS_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h index 30d77fa7a0..a4d85fb673 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_planner.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef _CHOMP_PLANNER_H_ -#define _CHOMP_PLANNER_H_ +#pragma once #include #include @@ -55,5 +54,3 @@ class ChompPlanner planning_interface::MotionPlanDetailedResponse& res) const; }; } - -#endif diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h index 359ce88b24..559237aa12 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_trajectory.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef CHOMP_TRAJECTORY_H_ -#define CHOMP_TRAJECTORY_H_ +#pragma once #include #include @@ -308,5 +307,3 @@ inline double ChompTrajectory::getDuration() const return duration_; } } - -#endif /* CHOMP_TRAJECTORY_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h index 0b9a5214ae..b5fb5b7a66 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_utils.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef CHOMP_UTILS_H_ -#define CHOMP_UTILS_H_ +#pragma once #include #include @@ -86,5 +85,3 @@ static inline double shortestAngularDistance(double start, double end) } } // namespace chomp - -#endif /* CHOMP_UTILS_H_ */ diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h index d906439cef..a1935d640e 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/multivariate_gaussian.h @@ -34,8 +34,7 @@ /* Author: Mrinal Kalakrishnan */ -#ifndef MULTIVARIATE_GAUSSIAN_H_ -#define MULTIVARIATE_GAUSSIAN_H_ +#pragma once #include #include @@ -93,5 +92,3 @@ void MultivariateGaussian::sample(Eigen::MatrixBase& output) output = mean_ + covariance_cholesky_ * output; } } - -#endif /* MULTIVARIATE_GAUSSIAN_H_ */ diff --git a/moveit_planners/ompl/ompl_interface/cfg/cpp/ompl_interface_ros/OMPLDynamicReconfigureConfig.h b/moveit_planners/ompl/ompl_interface/cfg/cpp/ompl_interface_ros/OMPLDynamicReconfigureConfig.h index fba9e700d3..4e85adddb2 100644 --- a/moveit_planners/ompl/ompl_interface/cfg/cpp/ompl_interface_ros/OMPLDynamicReconfigureConfig.h +++ b/moveit_planners/ompl/ompl_interface/cfg/cpp/ompl_interface_ros/OMPLDynamicReconfigureConfig.h @@ -43,8 +43,7 @@ // Author: Blaise Gassend -#ifndef __ompl_interface_ros__OMPLDYNAMICRECONFIGURECONFIG_H__ -#define __ompl_interface_ros__OMPLDYNAMICRECONFIGURECONFIG_H__ +#pragma once #include #include @@ -532,5 +531,3 @@ inline const OMPLDynamicReconfigureConfigStatics* OMPLDynamicReconfigureConfig:: return statics; } } - -#endif // __OMPLDYNAMICRECONFIGURERECONFIGURATOR_H__ diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/constraints_library.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/constraints_library.h index 7615ad1561..18c3888fc4 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/constraints_library.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/constraints_library.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_CONSTRAINTS_LIBRARY_ -#define MOVEIT_OMPL_INTERFACE_CONSTRAINTS_LIBRARY_ +#pragma once #include #include @@ -200,5 +199,3 @@ class ConstraintsLibrary std::map constraint_approximations_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h index 4eb0b16ec2..d054ab8e15 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_goal_sampler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_GOAL_SAMPLER_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_GOAL_SAMPLER_ +#pragma once #include #include @@ -73,5 +72,3 @@ class ConstrainedGoalSampler : public ompl::base::GoalLazySamples unsigned int verbose_display_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h index a0554bfbf7..cb72a22811 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_sampler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_SAMPLER_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_SAMPLER_ +#pragma once #include #include @@ -78,5 +77,3 @@ class ConstrainedSampler : public ompl::base::StateSampler double inv_dim_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_valid_state_sampler.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_valid_state_sampler.h index 7a504f7fbe..61e9b0d15d 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_valid_state_sampler.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constrained_valid_state_sampler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_VALID_STATE_SAMPLER_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINED_VALID_STATE_SAMPLER_ +#pragma once #include #include @@ -70,5 +69,3 @@ class ValidConstrainedSampler : public ompl::base::ValidStateSampler ompl::RNG rng_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h index 5636257e46..ccf47358ae 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/constraint_approximations.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINT_APPROXIMATION_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_CONSTRAINT_APPROXIMATION_ +#pragma once #include #include @@ -75,5 +74,3 @@ struct ConstraintApproximation MOVEIT_DECLARE_PTR(ConstraintApproximations, std::vector) } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h index 8fd837ad9d..63c0b0917f 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/projection_evaluators.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_PROJECTION_EVALUATORS_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_PROJECTION_EVALUATORS_ +#pragma once #include #include @@ -83,5 +82,3 @@ class ProjectionEvaluatorJointValue : public ompl::base::ProjectionEvaluator std::vector variables_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h index c485879007..23e02f87fb 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/state_validity_checker.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_ -#define MOVEIT_OMPL_INTERFACE_DETAIL_STATE_VALIDITY_CHECKER_ +#pragma once #include #include @@ -89,5 +88,3 @@ class StateValidityChecker : public ompl::base::StateValidityChecker bool verbose_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h index a19b69bfda..a276ede06e 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/detail/threadsafe_state_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_DEATIL_THREADSAFE_STATE_STORAGE_ -#define MOVEIT_OMPL_INTERFACE_DEATIL_THREADSAFE_STATE_STORAGE_ +#pragma once #include #include @@ -58,4 +57,3 @@ class TSStateStorage mutable std::mutex lock_; }; } -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h index 90f5034502..022aa4ab29 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_MODEL_BASED_PLANNING_CONTEXT_ -#define MOVEIT_OMPL_INTERFACE_MODEL_BASED_PLANNING_CONTEXT_ +#pragma once #include #include @@ -377,5 +376,3 @@ class ModelBasedPlanningContext : public planning_interface::PlanningContext bool simplify_solutions_; }; } // namespace ompl_interface - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 317272df62..5dc11716ee 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_ -#define MOVEIT_OMPL_INTERFACE_OMPL_INTERFACE_ +#pragma once #include #include @@ -193,5 +192,3 @@ class OMPLInterface constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h index 6b4dbb5229..4a8c9073fa 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_JOINT_SPACE_JOINT_MODEL_STATE_SPACE_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_JOINT_SPACE_JOINT_MODEL_STATE_SPACE_ +#pragma once #include @@ -49,5 +48,3 @@ class JointModelStateSpace : public ModelBasedStateSpace JointModelStateSpace(const ModelBasedStateSpaceSpecification& spec); }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h index 5ff8e4dab2..246f8a48e1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/joint_space/joint_model_state_space_factory.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_JOINT_SPACE_JOINT_MODEL_STATE_SPACE_FACTORY_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_JOINT_SPACE_JOINT_MODEL_STATE_SPACE_FACTORY_ +#pragma once #include @@ -53,5 +52,3 @@ class JointModelStateSpaceFactory : public ModelBasedStateSpaceFactory ModelBasedStateSpacePtr allocStateSpace(const ModelBasedStateSpaceSpecification& space_spec) const override; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h index 1bfa1379e6..106a4a2c41 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_ +#pragma once #include #include @@ -270,5 +269,3 @@ class ModelBasedStateSpace : public ompl::base::StateSpace double tag_snap_to_segment_complement_; }; } // namespace ompl_interface - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h index f369b52588..0bd363d9b2 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/model_based_state_space_factory.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_FACTORY_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_MODEL_BASED_STATE_SPACE_FACTORY_ +#pragma once #include #include @@ -75,5 +74,3 @@ class ModelBasedStateSpaceFactory std::string type_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h index 9f6fbaf9ee..a0d632c527 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_ +#pragma once #include #include @@ -136,5 +135,3 @@ class PoseModelStateSpace : public ModelBasedStateSpace double jump_factor_; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h index fc6d616d11..11f45ad066 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/parameterization/work_space/pose_model_state_space_factory.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_FACTORY_ -#define MOVEIT_OMPL_INTERFACE_PARAMETERIZATION_WORK_SPACE_POSE_MODEL_STATE_SPACE_FACTORY_ +#pragma once #include @@ -53,5 +52,3 @@ class PoseModelStateSpaceFactory : public ModelBasedStateSpaceFactory ModelBasedStateSpacePtr allocStateSpace(const ModelBasedStateSpaceSpecification& space_spec) const override; }; } - -#endif diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h index 4d08768b4b..c8d2f9fcb7 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/planning_context_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_ -#define MOVEIT_OMPL_INTERFACE_PLANNING_CONTEXT_MANAGER_ +#pragma once #include #include @@ -229,5 +228,3 @@ class PlanningContextManager CachedContextsPtr cached_contexts_; }; } - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bfs3d/BFS_3D.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bfs3d/BFS_3D.h index 8b60176b72..cf5700adf4 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bfs3d/BFS_3D.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bfs3d/BFS_3D.h @@ -34,8 +34,7 @@ /** \Author: Benjamin Cohen /bcohen@willowgarage.com, E. Gil Jones **/ -#ifndef _SBPL_BFS_3D_H_ -#define _SBPL_BFS_3D_H_ +#pragma once #include @@ -77,5 +76,3 @@ class BFS_3D int getDistance(int, int, int); }; } - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bresenham.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bresenham.h index 748bddf830..4f8f7847b9 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bresenham.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/bresenham.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef _BRESENHAM3D_ -#define _BRESENHAM3D_ +#pragma once #include #include @@ -56,5 +55,3 @@ void get_bresenham3d_parameters(int p1x, int p1y, int p1z, int p2x, int p2y, int void get_current_point3d(bresenham3d_param_t* params, int* x, int* y, int* z); int get_next_point3d(bresenham3d_param_t* params); - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/dummy_environment.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/dummy_environment.h index 3f9c43ba34..8dda73802e 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/dummy_environment.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/dummy_environment.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef _DUMMY_ENVIRONMENT_H_ -#define _DUMMY_ENVIRONMENT_H_ +#pragma once class DummyEnvironment : public DiscreteSpaceInformation { @@ -100,5 +99,3 @@ class DummyEnvironment : public DiscreteSpaceInformation { } }; - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h index e33fdec39e..5158a7f49d 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h @@ -34,8 +34,7 @@ /** \Author: Benjamin Cohen /bcohen@willowgarage.com, E. Gil Jones **/ -#ifndef _ENVIRONMENT_CHAIN3D_H_ -#define _ENVIRONMENT_CHAIN3D_H_ +#pragma once #include #include @@ -334,5 +333,3 @@ inline void EnvironmentChain3D::convertJointAnglesToCoord(const std::vector #include @@ -318,5 +317,3 @@ class SingleJointMotionPrimitive : public JointMotionPrimitive double delta_; }; } - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_interface.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_interface.h index 753211ccdb..61f5c91d80 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_interface.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_interface.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_SBPL_INTERFACE_H_ -#define MOVEIT_SBPL_INTERFACE_H_ +#pragma once #include #include @@ -68,5 +67,3 @@ class SBPLInterface // SBPLPlanner *planner_; }; } - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_meta_interface.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_meta_interface.h index 654d41b11d..dc41e7037f 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_meta_interface.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_meta_interface.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_SBPL_META_INTERFACE_H_ -#define MOVEIT_SBPL_META_INTERFACE_H_ +#pragma once #include #include @@ -77,5 +76,3 @@ class SBPLMetaInterface PlanningStatistics last_planning_statistics_; }; } - -#endif diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_params.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_params.h index 17e309740f..56c5a53f51 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_params.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/sbpl_params.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef _SBPL_PARAMS_H_ -#define _SBPL_PARAMS_H_ +#pragma once #include #include @@ -204,5 +203,3 @@ class SBPLParams std::vector motion_primitive_type_names_; }; } - -#endif diff --git a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h index c9527dfacd..9d39837d79 100644 --- a/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h +++ b/moveit_plugins/moveit_ros_control_interface/include/moveit_ros_control_interface/ControllerHandle.h @@ -34,8 +34,7 @@ /* Author: Mathias Lüdtke */ -#ifndef MOVEIT_ROS_CONTROL_INTERFACE_CONTROLLER_HANDLE_H -#define MOVEIT_ROS_CONTROL_INTERFACE_CONTROLLER_HANDLE_H +#pragma once #include #include @@ -58,5 +57,3 @@ class ControllerHandleAllocator }; } // namespace moveit_ros_control_interface - -#endif // MOVEIT_ROS_CONTROL_INTERFACE_CONTROLLER_HANDLE_H diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h index bfdee6d098..f3a5b8d059 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/action_based_controller_handle.h @@ -35,8 +35,7 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ -#ifndef MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE -#define MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE +#pragma once #include #include @@ -186,5 +185,3 @@ class ActionBasedControllerHandle : public ActionBasedControllerHandleBase }; } // end namespace moveit_simple_controller_manager - -#endif // MOVEIT_PLUGINS_ACTION_BASED_CONTROLLER_HANDLE diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h index dc01ccf011..4675b1c332 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/follow_joint_trajectory_controller_handle.h @@ -35,8 +35,7 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ -#ifndef MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE -#define MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE +#pragma once #include #include @@ -77,5 +76,3 @@ class FollowJointTrajectoryControllerHandle }; } // end namespace moveit_simple_controller_manager - -#endif // MOVEIT_PLUGINS_FOLLOW_TRAJECTORY_CONTROLLER_HANDLE diff --git a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h index e965d1b446..f081853850 100644 --- a/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h +++ b/moveit_plugins/moveit_simple_controller_manager/include/moveit_simple_controller_manager/gripper_controller_handle.h @@ -35,8 +35,7 @@ /* Author: Michael Ferguson, Ioan Sucan, E. Gil Jones */ -#ifndef MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE -#define MOVEIT_PLUGINS_GRIPPER_CONTROLLER_HANDLE +#pragma once #include #include @@ -218,5 +217,3 @@ class GripperControllerHandle : public ActionBasedControllerHandle @@ -226,5 +225,3 @@ class BenchmarkExecutor std::vector query_end_fns_; }; } - -#endif diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 0bc10321af..dbd46c4cdb 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -34,8 +34,7 @@ /* Author: Ryan Luna */ -#ifndef MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_ -#define MOVEIT_ROS_BENCHMARK_BENCHMARK_OPTIONS_ +#pragma once #include #include @@ -109,5 +108,3 @@ class BenchmarkOptions moveit_msgs::WorkspaceParameters workspace_; }; } - -#endif diff --git a/moveit_ros/manipulation/move_group_pick_place_capability/include/moveit/move_group_pick_place_capability/capability_names.h b/moveit_ros/manipulation/move_group_pick_place_capability/include/moveit/move_group_pick_place_capability/capability_names.h index 8058e204a4..95afa9e2b0 100644 --- a/moveit_ros/manipulation/move_group_pick_place_capability/include/moveit/move_group_pick_place_capability/capability_names.h +++ b/moveit_ros/manipulation/move_group_pick_place_capability/include/moveit/move_group_pick_place_capability/capability_names.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_PICK_PLACE_CAPABILITY_NAMES -#define MOVEIT_MOVE_GROUP_PICK_PLACE_CAPABILITY_NAMES +#pragma once #include @@ -44,5 +43,3 @@ namespace move_group static const std::string PICKUP_ACTION = "pickup"; // name of 'pickup' action static const std::string PLACE_ACTION = "place"; // name of 'place' action } - -#endif diff --git a/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.h b/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.h index d76e6244f2..3ba4abdb2f 100644 --- a/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.h +++ b/moveit_ros/manipulation/move_group_pick_place_capability/src/pick_place_action_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_PICK_PLACE_ACTION_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_PICK_PLACE_ACTION_CAPABILITY_ +#pragma once #include #include @@ -101,5 +100,3 @@ class MoveGroupPickPlaceAction : public MoveGroupCapability ros::ServiceClient grasp_planning_service_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/approach_and_translate_stage.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/approach_and_translate_stage.h index 2709de5136..fc1737229c 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/approach_and_translate_stage.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/approach_and_translate_stage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_PICK_PLACE_APPROACH_AND_TRANSLATE_STAGE_ -#define MOVEIT_PICK_PLACE_APPROACH_AND_TRANSLATE_STAGE_ +#pragma once #include #include @@ -62,5 +61,3 @@ class ApproachAndTranslateStage : public ManipulationStage double jump_factor_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h index f1bc6a920f..12b9dbf855 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_pipeline.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PICK_PLACE_MANIPULATION_PIPELINE_ -#define MOVEIT_PICK_PLACE_MANIPULATION_PIPELINE_ +#pragma once #include #include @@ -117,5 +116,3 @@ class ManipulationPipeline bool stop_processing_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_plan.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_plan.h index cc3ff2fe74..a8415864cf 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_plan.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_plan.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_PICK_PLACE_MANIPULATION_PLAN_ -#define MOVEIT_PICK_PLACE_MANIPULATION_PLAN_ +#pragma once #include #include @@ -143,5 +142,3 @@ struct ManipulationPlan std::size_t id_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_stage.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_stage.h index 5b36f9fb21..4b6e1f7b32 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_stage.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/manipulation_stage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_PICK_PLACE_MANIPULATION_STAGE_ -#define MOVEIT_PICK_PLACE_MANIPULATION_STAGE_ +#pragma once #include #include @@ -84,5 +83,3 @@ class ManipulationStage bool verbose_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h index 1507ebeaee..722dd3f79c 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PICK_PLACE_PICK_PLACE_ -#define MOVEIT_PICK_PLACE_PICK_PLACE_ +#pragma once #include #include @@ -165,5 +164,3 @@ class PickPlace : private boost::noncopyable, public std::enable_shared_from_thi constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place_params.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place_params.h index baabe4963d..08ae38837f 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place_params.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/pick_place_params.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PICK_PLACE_PICK_PLACE_PARAMS_ -#define MOVEIT_PICK_PLACE_PICK_PLACE_PARAMS_ +#pragma once namespace pick_place { @@ -52,5 +51,3 @@ struct PickPlaceParams // Get access to a global variable that contains the pick & place params. const PickPlaceParams& GetGlobalPickPlaceParams(); } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/plan_stage.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/plan_stage.h index 58a33e98d8..4810e44edf 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/plan_stage.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/plan_stage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_PICK_PLACE_PLAN_STAGE_ -#define MOVEIT_PICK_PLACE_PLAN_STAGE_ +#pragma once #include #include @@ -58,5 +57,3 @@ class PlanStage : public ManipulationStage planning_pipeline::PlanningPipelinePtr planning_pipeline_; }; } - -#endif diff --git a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/reachable_valid_pose_filter.h b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/reachable_valid_pose_filter.h index 7fe44f06bf..802c5dafe0 100644 --- a/moveit_ros/manipulation/pick_place/include/moveit/pick_place/reachable_valid_pose_filter.h +++ b/moveit_ros/manipulation/pick_place/include/moveit/pick_place/reachable_valid_pose_filter.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_PICK_PLACE_REACHABLE_VALID_POSE_FILTER_ -#define MOVEIT_PICK_PLACE_REACHABLE_VALID_POSE_FILTER_ +#pragma once #include #include @@ -60,5 +59,3 @@ class ReachableAndValidPoseFilter : public ManipulationStage constraint_samplers::ConstraintSamplerManagerPtr constraints_sampler_manager_; }; } - -#endif diff --git a/moveit_ros/move_group/include/moveit/move_group/capability_names.h b/moveit_ros/move_group/include/moveit/move_group/capability_names.h index 7b76ff727b..53f36e07a5 100644 --- a/moveit_ros/move_group/include/moveit/move_group/capability_names.h +++ b/moveit_ros/move_group/include/moveit/move_group/capability_names.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_DEFAULT_CAPABILITY_NAMES -#define MOVEIT_MOVE_GROUP_DEFAULT_CAPABILITY_NAMES +#pragma once #include @@ -64,5 +63,3 @@ static const std::string APPLY_PLANNING_SCENE_SERVICE_NAME = static const std::string CLEAR_OCTOMAP_SERVICE_NAME = "clear_octomap"; // name of the service that can be used to clear the octomap } - -#endif diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h index e92735fe81..c34ef2363d 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_CAPABILITY_ +#pragma once #include #include @@ -99,5 +98,3 @@ class MoveGroupCapability MoveGroupContextPtr context_; }; } - -#endif diff --git a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h index 845e155b3f..7808a6f3ea 100644 --- a/moveit_ros/move_group/include/moveit/move_group/move_group_context.h +++ b/moveit_ros/move_group/include/moveit/move_group/move_group_context.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_CONTEXT_ -#define MOVEIT_MOVE_GROUP_CONTEXT_ +#pragma once #include @@ -81,5 +80,3 @@ struct MoveGroupContext bool debug_; }; } - -#endif diff --git a/moveit_ros/move_group/include/moveit/move_group/node_name.h b/moveit_ros/move_group/include/moveit/move_group/node_name.h index 220dca0498..79d0ca4f16 100644 --- a/moveit_ros/move_group/include/moveit/move_group/node_name.h +++ b/moveit_ros/move_group/include/moveit/move_group/node_name.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_NODE_NAME -#define MOVEIT_MOVE_GROUP_NODE_NAME +#pragma once #include @@ -43,5 +42,3 @@ namespace move_group { static const std::string NODE_NAME = "move_group"; // name of node } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h index 3bcd7aeec2..9970cc8fef 100644 --- a/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/apply_planning_scene_service_capability.h @@ -34,8 +34,7 @@ /* Author: Michael 'v4hn' Goerner */ -#ifndef MOVEIT_MOVE_GROUP_APPLY_PLANNING_SCENE_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_APPLY_PLANNING_SCENE_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -59,5 +58,3 @@ class ApplyPlanningSceneService : public MoveGroupCapability ros::ServiceServer service_; }; } - -#endif // MOVEIT_MOVE_GROUP_APPLY_PLANNING_SCENE_SERVICE_CAPABILITY_ diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h index cf1fbe9a47..e90efe670c 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_CARTESIAN_PATH_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_CARTESIAN_PATH_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -57,5 +56,3 @@ class MoveGroupCartesianPathService : public MoveGroupCapability bool display_computed_paths_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h index 401a31f8f6..2c5e68b542 100644 --- a/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/clear_octomap_service_capability.h @@ -34,8 +34,7 @@ /* Author: David Hershberger */ -#ifndef MOVEIT_MOVE_GROUP_CLEAR_OCTOMAP_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_CLEAR_OCTOMAP_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -55,5 +54,3 @@ class ClearOctomapService : public MoveGroupCapability ros::ServiceServer service_; }; } - -#endif // MOVEIT_MOVE_GROUP_CLEAR_OCTOMAP_SERVICE_CAPABILITY_ diff --git a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h index c143b1e20b..f98965c8ba 100644 --- a/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/execute_trajectory_action_capability.h @@ -38,8 +38,7 @@ * Author: Kentaro Wada * */ -#ifndef MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ +#pragma once #include #include @@ -66,5 +65,3 @@ class MoveGroupExecuteTrajectoryAction : public MoveGroupCapability }; } // namespace move_group - -#endif // MOVEIT_MOVE_GROUP_EXECUTE_TRAJECTORY_ACTION_CAPABILITY_ diff --git a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h index 63fd7c35e7..c1cbfde2a7 100644 --- a/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/get_planning_scene_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_GET_PLANNING_SCENE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_GET_PLANNING_SCENE_CAPABILITY_ +#pragma once #include #include @@ -56,5 +55,3 @@ class MoveGroupGetPlanningSceneService : public MoveGroupCapability ros::ServiceServer get_scene_service_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h index d1f10a96a5..30e300ef47 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_KINEMATICS_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_KINEMATICS_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -63,5 +62,3 @@ class MoveGroupKinematicsService : public MoveGroupCapability ros::ServiceServer ik_service_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.h b/moveit_ros/move_group/src/default_capabilities/move_action_capability.h index d8af647a38..56917e6a67 100644 --- a/moveit_ros/move_group/src/default_capabilities/move_action_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/move_action_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_MOVE_ACTION_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_MOVE_ACTION_CAPABILITY_ +#pragma once #include #include @@ -71,5 +70,3 @@ class MoveGroupMoveAction : public MoveGroupCapability bool preempt_requested_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h index b3d7a94250..6ca33b6791 100644 --- a/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/plan_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_PLAN_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_PLAN_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -55,5 +54,3 @@ class MoveGroupPlanService : public MoveGroupCapability ros::ServiceServer plan_service_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h index 656c228a08..5d3a8b632f 100644 --- a/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/query_planners_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Robert Haschke */ -#ifndef MOVEIT_MOVE_GROUP_QUERY_PLANNERS_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_QUERY_PLANNERS_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -63,5 +62,3 @@ class MoveGroupQueryPlannersService : public MoveGroupCapability ros::ServiceServer set_service_; }; } - -#endif diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h index 2806a9586c..86dc6c8d52 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVE_GROUP_STATE_VALIDATION_SERVICE_CAPABILITY_ -#define MOVEIT_MOVE_GROUP_STATE_VALIDATION_SERVICE_CAPABILITY_ +#pragma once #include #include @@ -55,5 +54,3 @@ class MoveGroupStateValidationService : public MoveGroupCapability ros::ServiceServer validity_service_; }; } - -#endif diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h index e1cff913dd..70413b3d2c 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Jon Binney */ -#ifndef MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_ -#define MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_ +#pragma once #include #include @@ -116,5 +115,3 @@ class OccMapTree : public octomap::OcTree typedef std::shared_ptr OccMapTreePtr; typedef std::shared_ptr OccMapTreeConstPtr; } - -#endif diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h index 1558c434ae..ece0658606 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_monitor.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Jon Binney */ -#ifndef MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_ -#define MOVEIT_PERCEPTION_OCCUPANCY_MAP_MONITOR_ +#pragma once #include #include @@ -160,5 +159,3 @@ class OccupancyMapMonitor bool active_; }; } - -#endif diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h index cd91709567..07c2a0b0c8 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map_updater.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Jon Binney */ -#ifndef MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_ -#define MOVEIT_OCCUPANCY_MAP_MONITOR_OCCUPANCY_MAP_UPDATER_ +#pragma once #include #include @@ -112,5 +111,3 @@ class OccupancyMapUpdater static void readXmlParam(XmlRpc::XmlRpcValue& params, const std::string& param_name, unsigned int* value); }; } - -#endif diff --git a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h index d223e8d4b4..199c79204d 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h +++ b/moveit_ros/perception/depth_image_octomap_updater/include/moveit/depth_image_octomap_updater/depth_image_octomap_updater.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ -#define MOVEIT_OCCUPANCY_MAP_DEPTH_IMAGE_OCCUPANCY_MAP_UPDATER_ +#pragma once #include #include @@ -107,5 +106,3 @@ class DepthImageOctomapUpdater : public OccupancyMapUpdater ros::WallTime last_depth_callback_start_; }; } - -#endif diff --git a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h index cad8b0a48c..270ad565f1 100644 --- a/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h +++ b/moveit_ros/perception/lazy_free_space_updater/include/moveit/lazy_free_space_updater/lazy_free_space_updater.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_OCCUPANCY_MAP_MONITOR_LAZY_FREE_SPACE_UPDATER_ -#define MOVEIT_OCCUPANCY_MAP_MONITOR_LAZY_FREE_SPACE_UPDATER_ +#pragma once #include #include @@ -89,5 +88,3 @@ class LazyFreeSpaceUpdater boost::thread process_thread_; }; } - -#endif /* MOVEIT_OCCUPANCY_MAP_UPDATER_H_ */ diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h index 6ab4d6ab37..323bc03326 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/depth_self_filter_nodelet.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_DEPTH_SELF_FILTER_NODELET_ -#define MOVEIT_DEPTH_SELF_FILTER_NODELET_ +#pragma once #include #include @@ -132,5 +131,3 @@ class DepthSelfFiltering : public nodelet::Nodelet }; } // namespace mesh_filter - -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h index a1f098f244..a817245040 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/filter_job.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_FILTER_JOB_ -#define MOVEIT_MESH_FILTER_FILTER_JOB_ +#pragma once #include #include @@ -142,4 +141,3 @@ class FilterJob : public Job boost::function exec_; }; } -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h index 2ba940d7f7..a605425870 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_mesh.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_GLMESH_ -#define MOVEIT_MESH_FILTER_GLMESH_ +#pragma once #include #include @@ -85,4 +84,3 @@ class GLMesh unsigned int mesh_label_; }; } // namespace mesh_filter -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h index 67fa5abb1b..8ae3ee9f55 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/gl_renderer.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_GLRENDERER_ -#define MOVEIT_MESH_FILTER_GLRENDERER_ +#pragma once #include #include @@ -303,4 +302,3 @@ class GLRenderer static bool glutInitialized_; }; } // namespace mesh_filter -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h index e488aa2883..ed27f7b136 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_MESHFILTER_ -#define MOVEIT_MESH_FILTER_MESHFILTER_ +#pragma once #include #include @@ -112,4 +111,3 @@ const typename SensorType::Parameters& MeshFilter::parameters() cons } } // namespace mesh_filter -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h index 86f85270e0..dc8ee5f3f2 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/mesh_filter_base.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_MESH_FILTER_BASE_ -#define MOVEIT_MESH_FILTER_MESH_FILTER_BASE_ +#pragma once #include #include @@ -294,5 +293,3 @@ class MeshFilterBase float shadow_threshold_; }; } // namespace mesh_filter - -#endif /* __MESH_FILTER_MESH_FILTER_BASE_H__ */ diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h index 87239b0bd2..8c76cdccef 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/sensor_model.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_SENSOR_MODEL_ -#define MOVEIT_MESH_FILTER_SENSOR_MODEL_ +#pragma once #include #include @@ -170,5 +169,3 @@ class SensorModel virtual ~SensorModel(); }; } // namespace mesh_filter - -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h index 2dfac68ad6..d6dc185be1 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/stereo_camera_model.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_ -#define MOVEIT_MESH_FILTER_STEREO_CAMERA_MODEL_ +#pragma once #include #include @@ -164,4 +163,3 @@ class StereoCameraModel : public SensorModel static const std::string FILTER_FRAGMENT_SHADER_SOURCE; }; } // namespace mesh_filter -#endif diff --git a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h index fe5547edad..eb03286787 100644 --- a/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h +++ b/moveit_ros/perception/mesh_filter/include/moveit/mesh_filter/transform_provider.h @@ -34,8 +34,7 @@ /* Author: Suat Gedikli */ -#ifndef MOVEIT_MESH_FILTER_TRANSFORM_PROVIDER_ -#define MOVEIT_MESH_FILTER_TRANSFORM_PROVIDER_ +#pragma once #include #include @@ -167,4 +166,3 @@ class TransformProvider /** \brief update interval in micro seconds*/ unsigned long interval_us_; }; -#endif diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 2b6ee820bd..2fdf49c7b7 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_ -#define MOVEIT_POINT_CONTAINMENT_FILTER_SELF_MASK_ +#pragma once #include #include @@ -129,5 +128,3 @@ class ShapeMask std::vector bspheres_; }; } - -#endif diff --git a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h index cf56d68dfe..80ecbfaa11 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h +++ b/moveit_ros/perception/pointcloud_octomap_updater/include/moveit/pointcloud_octomap_updater/pointcloud_octomap_updater.h @@ -34,8 +34,7 @@ /* Author: Jon Binney, Ioan Sucan */ -#ifndef MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_ -#define MOVEIT_PERCEPTION_POINTCLOUD_OCTOMAP_UPDATER_ +#pragma once #include #include @@ -101,5 +100,3 @@ class PointCloudOctomapUpdater : public OccupancyMapUpdater std::vector mask_; }; } - -#endif diff --git a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h index bed034f0c9..b53e280328 100644 --- a/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h +++ b/moveit_ros/perception/semantic_world/include/moveit/semantic_world/semantic_world.h @@ -34,8 +34,7 @@ /* Author: Sachin Chitta */ -#ifndef MOVEIT_SEMANTIC_WORLD_ -#define MOVEIT_SEMANTIC_WORLD_ +#pragma once #include #include @@ -164,5 +163,3 @@ class SemanticWorld }; } } - -#endif diff --git a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h index 4527ae450e..b5709e824a 100644 --- a/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h +++ b/moveit_ros/planning/collision_plugin_loader/include/moveit/collision_plugin_loader/collision_plugin_loader.h @@ -32,8 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -#ifndef MOVEIT_COLLISION_PLUGIN_LOADER_COLLISION_PLUGIN_LOADER_H -#define MOVEIT_COLLISION_PLUGIN_LOADER_COLLISION_PLUGIN_LOADER_H +#pragma once #include #include @@ -68,5 +67,3 @@ class CollisionPluginLoader }; } // namespace collision_detection - -#endif // MOVEIT_COLLISION_PLUGIN_LOADER_COLLISION_PLUGIN_LOADER_H diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h index 5d24813893..84246d1851 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h +++ b/moveit_ros/planning/constraint_sampler_manager_loader/include/moveit/constraint_sampler_manager_loader/constraint_sampler_manager_loader.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_CONSTRAINT_SAMPLER_MANAGER_LOADER_ -#define MOVEIT_CONSTRAINT_SAMPLER_MANAGER_LOADER_ +#pragma once #include #include @@ -62,5 +61,3 @@ class ConstraintSamplerManagerLoader HelperPtr impl_; }; } - -#endif diff --git a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h index 9bc06594e3..f4c6b0a356 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h +++ b/moveit_ros/planning/kinematics_plugin_loader/include/moveit/kinematics_plugin_loader/kinematics_plugin_loader.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Dave Coleman */ -#ifndef MOVEIT_KINEMATICS_PLUGIN_LOADER_ -#define MOVEIT_KINEMATICS_PLUGIN_LOADER_ +#pragma once #include #include @@ -115,5 +114,3 @@ class KinematicsPluginLoader double default_solver_timeout_; }; } - -#endif diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h index e673c04031..11023522a9 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_execution.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLAN_EXECUTION_PLAN_EXECUTION_ -#define MOVEIT_PLAN_EXECUTION_PLAN_EXECUTION_ +#pragma once #include #include @@ -166,4 +165,3 @@ class PlanExecution DynamicReconfigureImpl* reconfigure_impl_; }; } -#endif diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h index c400874990..809cb259c7 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_representation.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLAN_EXECUTION_PLAN_REPRESENTATION_ -#define MOVEIT_PLAN_EXECUTION_PLAN_REPRESENTATION_ +#pragma once #include #include @@ -83,4 +82,3 @@ struct ExecutableMotionPlan /// The signature of a function that can compute a motion plan typedef boost::function ExecutableMotionPlanComputationFn; } -#endif diff --git a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h index 55a7d57f8a..b0b468cd19 100644 --- a/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h +++ b/moveit_ros/planning/plan_execution/include/moveit/plan_execution/plan_with_sensing.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ -#define MOVEIT_PLAN_EXECUTION_PLAN_WITH_SENSING_ +#pragma once #include #include @@ -135,4 +134,3 @@ class PlanWithSensing DynamicReconfigureImpl* reconfigure_impl_; }; } -#endif diff --git a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h index f08af40a04..313f770999 100644 --- a/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h +++ b/moveit_ros/planning/planning_pipeline/include/moveit/planning_pipeline/planning_pipeline.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_PIPELINE_PLANNING_PIPELINE_ -#define MOVEIT_PLANNING_PIPELINE_PLANNING_PIPELINE_ +#pragma once #include #include @@ -197,5 +196,3 @@ class PlanningPipeline MOVEIT_CLASS_FORWARD(PlanningPipeline); } - -#endif diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h index 709586792e..806db00daf 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/current_state_monitor.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_SCENE_MONITOR_CURRENT_STATE_MONITOR_ -#define MOVEIT_PLANNING_SCENE_MONITOR_CURRENT_STATE_MONITOR_ +#pragma once #include #include @@ -213,5 +212,3 @@ class CurrentStateMonitor MOVEIT_CLASS_FORWARD(CurrentStateMonitor); } - -#endif diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h index d03afd28ec..49db508c9f 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_SCENE_MONITOR_PLANNING_SCENE_MONITOR_ -#define MOVEIT_PLANNING_SCENE_MONITOR_PLANNING_SCENE_MONITOR_ +#pragma once #include #include @@ -702,5 +701,3 @@ class LockedPlanningSceneRW : public LockedPlanningSceneRO } }; } - -#endif diff --git a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h index 76e5e4562c..f7638161a7 100644 --- a/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h +++ b/moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/trajectory_monitor.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_SCENE_MONITOR_TRAJECTORY_MONITOR_ -#define MOVEIT_PLANNING_SCENE_MONITOR_TRAJECTORY_MONITOR_ +#pragma once #include #include @@ -107,5 +106,3 @@ class TrajectoryMonitor TrajectoryStateAddedCallback state_add_callback_; }; } - -#endif diff --git a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h index 76efd13c8e..bf506a96bf 100644 --- a/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h +++ b/moveit_ros/planning/rdf_loader/include/moveit/rdf_loader/rdf_loader.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Mathias Lüdtke, Dave Coleman */ -#ifndef MOVEIT_PLANNING_RDF_LOADER_ -#define MOVEIT_PLANNING_RDF_LOADER_ +#pragma once #include #include @@ -102,4 +101,3 @@ class RDFLoader urdf::ModelInterfaceSharedPtr urdf_; }; } -#endif diff --git a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h index def0d10d75..c39d9f1056 100644 --- a/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h +++ b/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_ -#define MOVEIT_PLANNING_MODELS_LOADER_ROBOT_MODEL_LOADER_ +#pragma once #include #include @@ -134,4 +133,3 @@ class RobotModelLoader kinematics_plugin_loader::KinematicsPluginLoaderPtr kinematics_loader_; }; } -#endif diff --git a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h index ea2f1a0d6d..1800068f42 100644 --- a/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/include/moveit/trajectory_execution_manager/trajectory_execution_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_TRAJECTORY_EXECUTION_MANAGER_TRAJECTORY_EXECUTION_MANAGER_ -#define MOVEIT_TRAJECTORY_EXECUTION_MANAGER_TRAJECTORY_EXECUTION_MANAGER_ +#pragma once #include #include @@ -362,5 +361,3 @@ class TrajectoryExecutionManager bool wait_for_trajectory_completion_; }; } - -#endif diff --git a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h index 731d2e65c4..46584f00cd 100644 --- a/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h +++ b/moveit_ros/planning/trajectory_execution_manager/test/test_moveit_controller_manager.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef TEST_MOVEIT_CONTROLLER_MANAGER_ -#define TEST_MOVEIT_CONTROLLER_MANAGER_ +#pragma once #include @@ -160,4 +159,3 @@ class TestMoveItControllerManager : public moveit_controller_manager::MoveItCont std::map > controller_joints_; }; } -#endif diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h index bffa91d836..10248a0f96 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h +++ b/moveit_ros/planning_interface/common_planning_interface_objects/include/moveit/common_planning_interface_objects/common_objects.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_INTERFACE_COMMON_OBJECTS_ -#define MOVEIT_PLANNING_INTERFACE_COMMON_OBJECTS_ +#pragma once #include @@ -73,5 +72,3 @@ planning_scene_monitor::CurrentStateMonitorPtr getSharedStateMonitor(const robot } // namespace planning interface } // namespace moveit - -#endif // end of MOVEIT_PLANNING_INTERFACE_COMMON_OBJECTS_ diff --git a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h index 1f919b0960..ae4d3a3b7d 100644 --- a/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h +++ b/moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan, Sachin Chitta */ -#ifndef MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_ -#define MOVEIT_MOVE_GROUP_INTERFACE_MOVE_GROUP_INTERFACE_ +#pragma once #include #include @@ -1003,5 +1002,3 @@ class MoveGroupInterface }; } // namespace planning_interface } // namespace moveit - -#endif diff --git a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h index d421b5484a..9dc25385e0 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h +++ b/moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_INTERFACE_PLANNING_SCENE_INTERFACE_ -#define MOVEIT_PLANNING_INTERFACE_PLANNING_SCENE_INTERFACE_ +#pragma once #include #include @@ -146,5 +145,3 @@ class PlanningSceneInterface }; } } - -#endif diff --git a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/py_conversions.h b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/py_conversions.h index fbf4d191ff..47825360ba 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/py_conversions.h +++ b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/py_conversions.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PY_BINDINGS_TOOLS_PY_CONVERSIONS_ -#define MOVEIT_PY_BINDINGS_TOOLS_PY_CONVERSIONS_ +#pragma once #include #include @@ -95,5 +94,3 @@ boost::python::list listFromString(const std::vector& v) } } } - -#endif diff --git a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h index e1e54a6bc9..1effb467a5 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h +++ b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/roscpp_initializer.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PY_BINDINGS_TOOLS_ROSCPP_INITIALIZER_ -#define MOVEIT_PY_BINDINGS_TOOLS_ROSCPP_INITIALIZER_ +#pragma once #include #include @@ -73,5 +72,3 @@ void roscpp_init(); void roscpp_shutdown(); } } - -#endif diff --git a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/serialize_msg.h b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/serialize_msg.h index 5000fccbbe..5b9a9a306f 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/serialize_msg.h +++ b/moveit_ros/planning_interface/py_bindings_tools/include/moveit/py_bindings_tools/serialize_msg.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PY_BINDINGS_TOOLS_SERIALIZE_MSG_ -#define MOVEIT_PY_BINDINGS_TOOLS_SERIALIZE_MSG_ +#pragma once #include @@ -71,5 +70,3 @@ void deserializeMsg(const std::string& data, T& msg) } } } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h index 1fdafbf667..b0027cf0f2 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley */ -#ifndef MOVEIT_ROBOT_INTERACTION_INTERACTION_ -#define MOVEIT_ROBOT_INTERACTION_INTERACTION_ +#pragma once #include #include @@ -175,5 +174,3 @@ struct JointInteraction double size; }; } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h index 5cc6ed89a5..3ea644e86a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interaction_handler.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Adam Leeper */ -#ifndef MOVEIT_ROBOT_INTERACTION_INTERACTION_HANDLER_ -#define MOVEIT_ROBOT_INTERACTION_INTERACTION_HANDLER_ +#pragma once #include #include @@ -311,5 +310,3 @@ class InteractionHandler : public LockedRobotState static std::string fixName(std::string name); }; } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h index 5810e7d244..16e821eab0 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/interactive_marker_helpers.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Acorn Pooley, Adam Leeper */ -#ifndef MOVEIT_ROBOT_INTERACTION_INTERACTIVE_MARKER_HELPERS_ -#define MOVEIT_ROBOT_INTERACTION_INTERACTIVE_MARKER_HELPERS_ +#pragma once #include #include @@ -69,5 +68,3 @@ void addPositionControl(visualization_msgs::InteractiveMarker& int_marker, bool void addViewPlaneControl(visualization_msgs::InteractiveMarker& int_marker, double radius, const std_msgs::ColorRGBA& color, bool position = true, bool orientation = true); } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h index 43b8e7bbc2..8a0248a60a 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley */ -#ifndef MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_ -#define MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_ +#pragma once #include #include @@ -89,5 +88,3 @@ struct KinematicOptions kinematics::KinematicsQueryOptions options_; }; } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h index 033fd0ac4b..f9c6a986b9 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/kinematic_options_map.h @@ -34,8 +34,7 @@ /* Author: Acorn Pooley */ -#ifndef MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_MAP_ -#define MOVEIT_ROBOT_INTERACTION_KINEMATIC_OPTIONS_MAP_ +#pragma once #include #include @@ -104,5 +103,3 @@ class KinematicOptionsMap M_options options_; }; } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h index 286a86a95d..fd6b3f3616 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/locked_robot_state.h @@ -35,8 +35,7 @@ /* Author: Ioan Sucan, Acorn Pooley */ -#ifndef MOVEIT_ROBOT_INTERACTION_LOCKED_ROBOT_STATE_ -#define MOVEIT_ROBOT_INTERACTION_LOCKED_ROBOT_STATE_ +#pragma once #include #include @@ -109,5 +108,3 @@ class LockedRobotState robot_state::RobotStatePtr state_; }; } - -#endif diff --git a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h index a5ebcc0001..494386af0f 100644 --- a/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h +++ b/moveit_ros/robot_interaction/include/moveit/robot_interaction/robot_interaction.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Adam Leeper */ -#ifndef MOVEIT_ROBOT_INTERACTION_ROBOT_INTERACTION_ -#define MOVEIT_ROBOT_INTERACTION_ROBOT_INTERACTION_ +#pragma once #include #include @@ -234,5 +233,3 @@ class RobotInteraction KinematicOptionsMapPtr kinematic_options_map_; }; } - -#endif diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h index a8c30c9cb0..52cd9b5640 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_display.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan, Dave Coleman, Adam Leeper, Sachin Chitta */ -#ifndef MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_DISPLAY_ -#define MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_DISPLAY_ +#pragma once #include #include @@ -301,5 +300,3 @@ private Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index d49e100204..c212905f5f 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_FRAME_ -#define MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_FRAME_ +#pragma once #include #include @@ -365,5 +364,3 @@ void MotionPlanningFrame::waitForAction(const T& action, const ros::NodeHandle& ROS_DEBUG("Connected to '%s'", name.c_str()); }; } - -#endif diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h index 91242225c4..99658c4f2d 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_param_widget.h @@ -34,8 +34,7 @@ /* Author: Robert Haschke */ -#ifndef MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_PARAM_WIDGET_ -#define MOVEIT_MOTION_PLANNING_RVIZ_PLUGIN_MOTION_PLANNING_PARAM_WIDGET_ +#pragma once #include #include @@ -77,5 +76,3 @@ private Q_SLOTS: std::string planner_id_; }; } - -#endif diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h index b18c4a0140..06e30bef58 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/include/moveit/planning_scene_rviz_plugin/planning_scene_display.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_ -#define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_SCENE_DISPLAY_ +#pragma once #include @@ -213,5 +212,3 @@ protected Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h index c1692d94d7..e087dd3a62 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h +++ b/moveit_ros/visualization/robot_state_rviz_plugin/include/moveit/robot_state_rviz_plugin/robot_state_display.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_ -#define MOVEIT_VISUALIZATION_ROBOT_STATE_DISPLAY_RVIZ_ROBOT_STATE_DISPLAY_ +#pragma once #include @@ -146,5 +145,3 @@ private Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h index 92bd6dd2bb..9c4f3c60b2 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/octomap_render.h @@ -34,8 +34,7 @@ /* Author: Julius Kammerl */ -#ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_OCTOMAP_RENDER_ -#define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_OCTOMAP_RENDER_ +#pragma once #include #include @@ -100,4 +99,3 @@ class OcTreeRender std::size_t octree_depth_; }; } -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h index 0f8f417f37..0d757ef7c5 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_link_updater.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PLANNING_LINK_UPDATER_ -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_PLANNING_LINK_UPDATER_ +#pragma once #include #include @@ -58,5 +57,3 @@ class PlanningLinkUpdater : public rviz::LinkUpdater robot_state::RobotStateConstPtr kinematic_state_; }; } - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h index 84106db313..987425752c 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/planning_scene_render.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_PLANNING_SCENE_RENDER_ -#define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_PLUGIN_PLANNING_SCENE_RENDER_ +#pragma once #include #include @@ -88,5 +87,3 @@ class PlanningSceneRender RobotStateVisualizationPtr scene_robot_; }; } - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h index fa891bcccd..808d91b710 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/render_shapes.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_RENDER_SHAPES_ -#define MOVEIT_VISUALIZATION_SCENE_DISPLAY_RVIZ_RENDER_SHAPES_ +#pragma once #include #include @@ -79,5 +78,3 @@ class RenderShapes std::vector octree_voxel_grids_; }; } - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 24f246dcc3..49b299f1d1 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_ -#define MOVEIT_PLANNING_SCENE_RVIZ_PLUGIN_ROBOT_STATE_VISUALIZATION_ +#pragma once #include #include @@ -105,5 +104,3 @@ class RobotStateVisualization bool collision_visible_; }; } - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h index e4c7d731d1..c552f7ec84 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_panel.h @@ -34,8 +34,7 @@ /* Author: Yannick Jonetzko */ -#ifndef MOVEIT_TRAJECTORY_RVIZ_PLUGIN_TRAJECTORY_PANEL_ -#define MOVEIT_TRAJECTORY_RVIZ_PLUGIN_TRAJECTORY_PANEL_ +#pragma once #ifndef Q_MOC_RUN #include @@ -93,5 +92,3 @@ private Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h index 1c309a46d7..23aa020bf6 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/trajectory_visualization.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION -#define MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_VISUALIZATION +#pragma once #include #include @@ -170,5 +169,3 @@ private Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h index 209778d44f..d4c0ab28a8 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h +++ b/moveit_ros/visualization/trajectory_rviz_plugin/include/moveit/trajectory_rviz_plugin/trajectory_display.h @@ -36,8 +36,7 @@ Desc: Wraps a trajectory_visualization playback class for Rviz into a stand alone display */ -#ifndef MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_DISPLAY -#define MOVEIT_TRAJECTORY_RVIZ_PLUGIN__TRAJECTORY_DISPLAY +#pragma once #include @@ -96,5 +95,3 @@ private Q_SLOTS: }; } // namespace moveit_rviz_plugin - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h index 4bee5469a5..7e507bb257 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/constraints_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_CONSTRAINTS_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_CONSTRAINTS_STORAGE_ +#pragma once #include "moveit/warehouse/moveit_message_storage.h" #include @@ -84,5 +83,3 @@ class ConstraintsStorage : public MoveItMessageStorage ConstraintsCollection constraints_collection_; }; } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/moveit_message_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/moveit_message_storage.h index 6b8b179258..f6b6be0c3e 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/moveit_message_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/moveit_message_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_MOVEIT_MESSAGE_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_MOVEIT_MESSAGE_STORAGE_ +#pragma once #include #include @@ -66,5 +65,3 @@ class MoveItMessageStorage /// \brief Load a database connection typename warehouse_ros::DatabaseConnection::Ptr loadDatabase(); } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h index ec7d65c4b3..1878942ecd 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_STORAGE_ +#pragma once #include "moveit/warehouse/moveit_message_storage.h" #include @@ -120,5 +119,3 @@ class PlanningSceneStorage : public MoveItMessageStorage RobotTrajectoryCollection robot_trajectory_collection_; }; } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_world_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_world_storage.h index bafb6ab688..fec6384e54 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_world_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/planning_scene_world_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_WORLD_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_PLANNING_SCENE_WORLD_STORAGE_ +#pragma once #include #include @@ -73,5 +72,3 @@ class PlanningSceneWorldStorage : public MoveItMessageStorage PlanningSceneWorldCollection planning_scene_world_collection_; }; } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h index fed8808143..ce592f9fa0 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/state_storage.h @@ -34,8 +34,7 @@ /* Author: Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_STATE_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_STATE_STORAGE_ +#pragma once #include #include @@ -79,5 +78,3 @@ class RobotStateStorage : public MoveItMessageStorage RobotStateCollection state_collection_; }; } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h index 1b0cbe501d..7246618a41 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/trajectory_constraints_storage.h @@ -34,8 +34,7 @@ /* Author: Mario Prats, Ioan Sucan */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_TRAJECTORY_CONSTRAINTS_STORAGE_ -#define MOVEIT_MOVEIT_WAREHOUSE_TRAJECTORY_CONSTRAINTS_STORAGE_ +#pragma once #include "moveit/warehouse/moveit_message_storage.h" #include @@ -87,5 +86,3 @@ class TrajectoryConstraintsStorage : public MoveItMessageStorage TrajectoryConstraintsCollection constraints_collection_; }; } - -#endif diff --git a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/warehouse_connector.h b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/warehouse_connector.h index d61df45bae..3555097ccd 100644 --- a/moveit_ros/warehouse/warehouse/include/moveit/warehouse/warehouse_connector.h +++ b/moveit_ros/warehouse/warehouse/include/moveit/warehouse/warehouse_connector.h @@ -34,8 +34,7 @@ /* Author: E. Gil Jones */ -#ifndef MOVEIT_MOVEIT_WAREHOUSE_WAREHOUSE_CONNECTOR_ -#define MOVEIT_MOVEIT_WAREHOUSE_WAREHOUSE_CONNECTOR_ +#pragma once #include @@ -55,5 +54,3 @@ class WarehouseConnector int child_pid_; }; } - -#endif diff --git a/moveit_setup_assistant/include/moveit/setup_assistant/tools/compute_default_collisions.h b/moveit_setup_assistant/include/moveit/setup_assistant/tools/compute_default_collisions.h index 207e24bd13..c19bc2e0f5 100644 --- a/moveit_setup_assistant/include/moveit/setup_assistant/tools/compute_default_collisions.h +++ b/moveit_setup_assistant/include/moveit/setup_assistant/tools/compute_default_collisions.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_COMPUTE_DEFAULT_COLLISIONS_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_COMPUTE_DEFAULT_COLLISIONS_ +#pragma once #include #include @@ -110,5 +109,3 @@ const std::string disabledReasonToString(DisabledReason reason); */ DisabledReason disabledReasonFromString(const std::string& reason); } - -#endif diff --git a/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h b/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h index c30ad62283..0e42bac586 100644 --- a/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h +++ b/moveit_setup_assistant/include/moveit/setup_assistant/tools/moveit_config_data.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_TOOLS_MOVEIT_CONFIG_DATA_ +#pragma once #include #include // for getting kinematic model @@ -525,5 +524,3 @@ class MoveItConfigData }; } // namespace - -#endif diff --git a/moveit_setup_assistant/src/tools/collision_linear_model.h b/moveit_setup_assistant/src/tools/collision_linear_model.h index 9744170243..9b702fcc73 100644 --- a/moveit_setup_assistant/src/tools/collision_linear_model.h +++ b/moveit_setup_assistant/src/tools/collision_linear_model.h @@ -34,8 +34,7 @@ /* Author: Robert Haschke */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_LINEAR_MODEL_H -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_LINEAR_MODEL_H +#pragma once #include #include @@ -100,5 +99,3 @@ private Q_SLOTS: QVector sort_columns_; // sorting history QVector sort_orders_; // corresponding sort orders }; - -#endif // MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_LINEAR_MODEL_H diff --git a/moveit_setup_assistant/src/tools/collision_matrix_model.h b/moveit_setup_assistant/src/tools/collision_matrix_model.h index dccbc2eed1..ed5d67e894 100644 --- a/moveit_setup_assistant/src/tools/collision_matrix_model.h +++ b/moveit_setup_assistant/src/tools/collision_matrix_model.h @@ -34,8 +34,7 @@ /* Author: Robert Haschke */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_MATRIX_MODEL_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_MATRIX_MODEL_ +#pragma once #include @@ -79,5 +78,3 @@ public Q_SLOTS: QList q_names; // names of links QList visual_to_index; // map from visual index to actual index }; - -#endif // MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_COLLISION_MATRIX_MODEL_ diff --git a/moveit_setup_assistant/src/tools/rotated_header_view.h b/moveit_setup_assistant/src/tools/rotated_header_view.h index 27854b7140..5bf288d84c 100644 --- a/moveit_setup_assistant/src/tools/rotated_header_view.h +++ b/moveit_setup_assistant/src/tools/rotated_header_view.h @@ -34,8 +34,7 @@ /* Author: Robert Haschke */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROTATED_HEADERVIEW_H -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROTATED_HEADERVIEW_H +#pragma once #include @@ -50,5 +49,3 @@ class RotatedHeaderView : public QHeaderView int sectionSizeHint(int logicalIndex) const; }; } - -#endif // MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROTATED_HEADERVIEW_H diff --git a/moveit_setup_assistant/src/widgets/author_information_widget.h b/moveit_setup_assistant/src/widgets/author_information_widget.h index 15ed0036ec..94763edf93 100644 --- a/moveit_setup_assistant/src/widgets/author_information_widget.h +++ b/moveit_setup_assistant/src/widgets/author_information_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman, Michael 'v4hn' Goerner */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_AUTHOR_INFORMATION_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_AUTHOR_INFORMATION_WIDGET_ +#pragma once #include #include @@ -86,5 +85,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.h b/moveit_setup_assistant/src/widgets/configuration_files_widget.h index f0787af004..da0946e4dd 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.h +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONFIGURATION_FILES_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONFIGURATION_FILES_WIDGET_ +#pragma once #include #include @@ -205,5 +204,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/controller_edit_widget.h b/moveit_setup_assistant/src/widgets/controller_edit_widget.h index 2113005c8a..f7a2679164 100644 --- a/moveit_setup_assistant/src/widgets/controller_edit_widget.h +++ b/moveit_setup_assistant/src/widgets/controller_edit_widget.h @@ -33,8 +33,7 @@ /* Author: Mohamad Ayman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONTROLLER_EDIT_WIDGET_H -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONTROLLER_EDIT_WIDGET_H +#pragma once #include #include @@ -142,5 +141,3 @@ private Q_SLOTS: moveit_setup_assistant::MoveItConfigDataPtr config_data_; }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/default_collisions_widget.h b/moveit_setup_assistant/src/widgets/default_collisions_widget.h index cef78d3c0b..d69cedefd3 100644 --- a/moveit_setup_assistant/src/widgets/default_collisions_widget.h +++ b/moveit_setup_assistant/src/widgets/default_collisions_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_DEFAULT_COLLISIONS_WIDGET__ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_DEFAULT_COLLISIONS_WIDGET__ +#pragma once #include #include @@ -257,5 +256,3 @@ class MonitorThread : public QThread bool canceled_; }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/double_list_widget.h b/moveit_setup_assistant/src/widgets/double_list_widget.h index c4e511bd14..1d983134aa 100644 --- a/moveit_setup_assistant/src/widgets/double_list_widget.h +++ b/moveit_setup_assistant/src/widgets/double_list_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_DOUBLE_LIST_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_DOUBLE_LIST_WIDGET_ +#pragma once #include #include @@ -141,5 +140,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/end_effectors_widget.h b/moveit_setup_assistant/src/widgets/end_effectors_widget.h index 1c5b17247c..a6be88ed6f 100644 --- a/moveit_setup_assistant/src/widgets/end_effectors_widget.h +++ b/moveit_setup_assistant/src/widgets/end_effectors_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_END_EFFECTORS_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_END_EFFECTORS_WIDGET_ +#pragma once // Qt #include @@ -184,5 +183,3 @@ private Q_SLOTS: }; } // namespace - -#endif diff --git a/moveit_setup_assistant/src/widgets/group_edit_widget.h b/moveit_setup_assistant/src/widgets/group_edit_widget.h index e5ae0ec884..60a6a67b6e 100644 --- a/moveit_setup_assistant/src/widgets/group_edit_widget.h +++ b/moveit_setup_assistant/src/widgets/group_edit_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_GROUP_EDIT_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_GROUP_EDIT_WIDGET_ +#pragma once #include #include @@ -127,5 +126,3 @@ private Q_SLOTS: // ****************************************************************************************** }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/header_widget.h b/moveit_setup_assistant/src/widgets/header_widget.h index 40793d36a0..a5661beb83 100644 --- a/moveit_setup_assistant/src/widgets/header_widget.h +++ b/moveit_setup_assistant/src/widgets/header_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_HEADER_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_HEADER_WIDGET_ +#pragma once #include #include @@ -119,5 +118,3 @@ class LoadPathArgsWidget : public LoadPathWidget void setArgsEnabled(bool enabled = true); }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/kinematic_chain_widget.h b/moveit_setup_assistant/src/widgets/kinematic_chain_widget.h index da63182675..4c5764cdfd 100644 --- a/moveit_setup_assistant/src/widgets/kinematic_chain_widget.h +++ b/moveit_setup_assistant/src/widgets/kinematic_chain_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_KINEMATIC_CHAIN_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_KINEMATIC_CHAIN_WIDGET_ +#pragma once #include #include @@ -135,5 +134,3 @@ private Q_SLOTS: // ****************************************************************************************** }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/navigation_widget.h b/moveit_setup_assistant/src/widgets/navigation_widget.h index 962a7d1dc0..76084c869e 100644 --- a/moveit_setup_assistant/src/widgets/navigation_widget.h +++ b/moveit_setup_assistant/src/widgets/navigation_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_NAVIGATION_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_NAVIGATION_WIDGET_ +#pragma once #include #include @@ -84,5 +83,3 @@ class NavDelegate : public QStyledItemDelegate void paint(QPainter* painter, const QStyleOptionViewItem& option, const QModelIndex& index) const override; }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/passive_joints_widget.h b/moveit_setup_assistant/src/widgets/passive_joints_widget.h index c7dc8dd1d5..344b133d3a 100644 --- a/moveit_setup_assistant/src/widgets/passive_joints_widget.h +++ b/moveit_setup_assistant/src/widgets/passive_joints_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PASSIVE_JOINTS_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PASSIVE_JOINTS_WIDGET_ +#pragma once // Qt #include @@ -102,5 +101,3 @@ private Q_SLOTS: }; } // namespace - -#endif diff --git a/moveit_setup_assistant/src/widgets/perception_widget.h b/moveit_setup_assistant/src/widgets/perception_widget.h index 336fe8a80e..e9c6952d6d 100644 --- a/moveit_setup_assistant/src/widgets/perception_widget.h +++ b/moveit_setup_assistant/src/widgets/perception_widget.h @@ -33,8 +33,7 @@ /* Author: Mohamad Ayman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PERCEPTION_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PERCEPTION_WIDGET_ +#pragma once // Qt #include @@ -125,5 +124,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/planning_groups_widget.h b/moveit_setup_assistant/src/widgets/planning_groups_widget.h index 85bcf64259..0d40c6cc9e 100644 --- a/moveit_setup_assistant/src/widgets/planning_groups_widget.h +++ b/moveit_setup_assistant/src/widgets/planning_groups_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PLANNING_GROUPS_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_PLANNING_GROUPS_WIDGET_ +#pragma once // Qt class QPushButton; @@ -232,5 +231,3 @@ class PlanGroupType }; Q_DECLARE_METATYPE(PlanGroupType); - -#endif diff --git a/moveit_setup_assistant/src/widgets/robot_poses_widget.h b/moveit_setup_assistant/src/widgets/robot_poses_widget.h index 6614273cca..bdf6aa3e2f 100644 --- a/moveit_setup_assistant/src/widgets/robot_poses_widget.h +++ b/moveit_setup_assistant/src/widgets/robot_poses_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROBOT_POSES_WIDGET_ +#pragma once // Qt #include @@ -295,5 +294,3 @@ private Q_SLOTS: // Declare std::string as metatype so we can use it in a signal Q_DECLARE_METATYPE(std::string) - -#endif diff --git a/moveit_setup_assistant/src/widgets/ros_controllers_widget.h b/moveit_setup_assistant/src/widgets/ros_controllers_widget.h index 57fc7d3c8b..c1c05e609b 100644 --- a/moveit_setup_assistant/src/widgets/ros_controllers_widget.h +++ b/moveit_setup_assistant/src/widgets/ros_controllers_widget.h @@ -33,8 +33,7 @@ /* Author: Mohamad Ayman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROS_CONTROLLERS_WIDGET_H -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_ROS_CONTROLLERS_WIDGET_H +#pragma once // Qt #include @@ -160,5 +159,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h index 48ccf7d26a..51f07cf56f 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_SETUP_ASSISTANT_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_SETUP_ASSISTANT_WIDGET_ +#pragma once // Qt #include @@ -237,5 +236,3 @@ private Q_SLOTS: // ****************************************************************************************** }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/setup_screen_widget.h b/moveit_setup_assistant/src/widgets/setup_screen_widget.h index 805350e9d5..7898b4f25e 100644 --- a/moveit_setup_assistant/src/widgets/setup_screen_widget.h +++ b/moveit_setup_assistant/src/widgets/setup_screen_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_SETUP_SCREEN_WIDGET_ -#define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_SETUP_SCREEN_WIDGET_ +#pragma once #include @@ -75,5 +74,3 @@ class SetupScreenWidget : public QWidget /// Event for telling rviz to unhighlight all links of the robot void unhighlightAll(); }; - -#endif diff --git a/moveit_setup_assistant/src/widgets/simulation_widget.h b/moveit_setup_assistant/src/widgets/simulation_widget.h index 2b3ac58331..029874d065 100644 --- a/moveit_setup_assistant/src/widgets/simulation_widget.h +++ b/moveit_setup_assistant/src/widgets/simulation_widget.h @@ -33,8 +33,7 @@ /* Author: Mohamad Ayman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_SIMULATION_WIDGET_H -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_SIMULATION_WIDGET_H +#pragma once // Qt #include @@ -93,5 +92,3 @@ private Q_SLOTS: }; } // namespace moveit_setup_assistant - -#endif diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.h b/moveit_setup_assistant/src/widgets/start_screen_widget.h index 8a75e38c58..d06dd6a6ce 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.h +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_START_SCREEN_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_START_SCREEN_WIDGET_ +#pragma once #include #include @@ -190,5 +189,3 @@ private Q_SLOTS: QLabel* widget_instructions_; }; } - -#endif diff --git a/moveit_setup_assistant/src/widgets/virtual_joints_widget.h b/moveit_setup_assistant/src/widgets/virtual_joints_widget.h index b1bb87a68b..e3c6f5d4ec 100644 --- a/moveit_setup_assistant/src/widgets/virtual_joints_widget.h +++ b/moveit_setup_assistant/src/widgets/virtual_joints_widget.h @@ -34,8 +34,7 @@ /* Author: Dave Coleman */ -#ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_VIRTUAL_JOINTS_WIDGET_ -#define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_VIRTUAL_JOINTS_WIDGET_ +#pragma once // Qt #include @@ -188,5 +187,3 @@ private Q_SLOTS: }; } // namespace - -#endif From a6f8ff994172ba504fecfeddbaf9de02a75010e1 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Tue, 13 Aug 2019 04:49:19 -0500 Subject: [PATCH 25/96] Update jog_arm README with rviz config (#1614) --- moveit_experimental/jog_arm/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_experimental/jog_arm/README.md b/moveit_experimental/jog_arm/README.md index 7e3626d94d..af983f78d6 100644 --- a/moveit_experimental/jog_arm/README.md +++ b/moveit_experimental/jog_arm/README.md @@ -16,7 +16,7 @@ Build and subsequently source the catkin workspace. Startup the robot and MoveIt roslaunch ur5_moveit_config ur5_moveit_planning_execution.launch sim:=true - roslaunch ur5_moveit_config moveit_rviz.launch + roslaunch ur5_moveit_config moveit_rviz.launch config:=true In RViz, "plan and execute" a motion to a non-singular position (not all zero joint angles) that is not close to a joint limit. From 9ddbfb25c92c35559090a6c8a3a1a2b501fa6653 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Tue, 13 Aug 2019 11:44:42 -0700 Subject: [PATCH 26/96] Fix binary artifact install locations. (#1575) --- moveit_core/background_processing/CMakeLists.txt | 3 ++- moveit_core/collision_detection/CMakeLists.txt | 3 ++- .../collision_detection_fcl/CMakeLists.txt | 3 ++- .../collision_distance_field/CMakeLists.txt | 2 +- moveit_core/constraint_samplers/CMakeLists.txt | 3 ++- moveit_core/distance_field/CMakeLists.txt | 3 ++- moveit_core/dynamics_solver/CMakeLists.txt | 3 ++- moveit_core/exceptions/CMakeLists.txt | 3 ++- moveit_core/kinematic_constraints/CMakeLists.txt | 3 ++- moveit_core/kinematics_base/CMakeLists.txt | 3 ++- moveit_core/kinematics_metrics/CMakeLists.txt | 3 ++- moveit_core/planning_interface/CMakeLists.txt | 3 ++- .../planning_request_adapter/CMakeLists.txt | 3 ++- moveit_core/planning_scene/CMakeLists.txt | 3 ++- moveit_core/profiler/CMakeLists.txt | 3 ++- moveit_core/robot_model/CMakeLists.txt | 3 ++- moveit_core/robot_state/CMakeLists.txt | 3 ++- moveit_core/robot_trajectory/CMakeLists.txt | 3 ++- moveit_core/trajectory_processing/CMakeLists.txt | 3 ++- moveit_core/transforms/CMakeLists.txt | 3 ++- moveit_core/utils/CMakeLists.txt | 3 ++- .../v2/kinematics_cache/CMakeLists.txt | 5 ++++- .../kinematics_constraint_aware/CMakeLists.txt | 5 ++++- .../cached_ik_kinematics_plugin/CMakeLists.txt | 15 ++++++++++++--- .../templates/CMakeLists.txt | 4 +++- .../kdl_kinematics_plugin/CMakeLists.txt | 5 ++++- .../lma_kinematics_plugin/CMakeLists.txt | 5 ++++- .../srv_kinematics_plugin/CMakeLists.txt | 5 ++++- moveit_kinematics/test/CMakeLists.txt | 3 ++- .../chomp/chomp_interface/CMakeLists.txt | 2 +- .../chomp/chomp_motion_planner/CMakeLists.txt | 2 +- .../chomp/chomp_optimizer_adapter/CMakeLists.txt | 2 +- .../ompl/ompl_interface/CMakeLists.txt | 5 ++++- .../moveit_fake_controller_manager/CMakeLists.txt | 5 ++++- .../moveit_ros_control_interface/CMakeLists.txt | 2 +- .../CMakeLists.txt | 5 ++++- moveit_ros/benchmarks/CMakeLists.txt | 8 +++++++- .../CMakeLists.txt | 3 ++- moveit_ros/manipulation/pick_place/CMakeLists.txt | 5 ++++- moveit_ros/move_group/CMakeLists.txt | 7 +++++-- moveit_ros/occupancy_map_monitor/CMakeLists.txt | 9 +++++++-- .../depth_image_octomap_updater/CMakeLists.txt | 5 ++++- .../lazy_free_space_updater/CMakeLists.txt | 5 ++++- moveit_ros/perception/mesh_filter/CMakeLists.txt | 5 ++++- .../point_containment_filter/CMakeLists.txt | 5 ++++- .../pointcloud_octomap_updater/CMakeLists.txt | 3 ++- .../perception/semantic_world/CMakeLists.txt | 3 ++- .../collision_plugin_loader/CMakeLists.txt | 5 ++++- .../CMakeLists.txt | 5 ++++- .../kinematics_plugin_loader/CMakeLists.txt | 5 ++++- moveit_ros/planning/plan_execution/CMakeLists.txt | 5 ++++- .../planning/planning_pipeline/CMakeLists.txt | 5 ++++- .../CMakeLists.txt | 6 +++++- .../planning_scene_monitor/CMakeLists.txt | 5 ++++- moveit_ros/planning/rdf_loader/CMakeLists.txt | 5 ++++- .../planning/robot_model_loader/CMakeLists.txt | 5 ++++- .../trajectory_execution_manager/CMakeLists.txt | 5 ++++- .../CMakeLists.txt | 3 ++- .../move_group_interface/CMakeLists.txt | 6 ++++-- .../planning_scene_interface/CMakeLists.txt | 6 +++--- .../py_bindings_tools/CMakeLists.txt | 6 +++--- .../robot_interface/CMakeLists.txt | 3 +-- moveit_ros/robot_interaction/CMakeLists.txt | 5 ++++- .../motion_planning_rviz_plugin/CMakeLists.txt | 3 ++- .../planning_scene_rviz_plugin/CMakeLists.txt | 3 ++- .../robot_state_rviz_plugin/CMakeLists.txt | 3 ++- .../rviz_plugin_render_tools/CMakeLists.txt | 3 ++- .../trajectory_rviz_plugin/CMakeLists.txt | 3 ++- moveit_ros/warehouse/warehouse/CMakeLists.txt | 7 ++++++- moveit_setup_assistant/CMakeLists.txt | 9 +++++++-- 70 files changed, 220 insertions(+), 81 deletions(-) diff --git a/moveit_core/background_processing/CMakeLists.txt b/moveit_core/background_processing/CMakeLists.txt index 0e09ddc409..f0b7ab4712 100644 --- a/moveit_core/background_processing/CMakeLists.txt +++ b/moveit_core/background_processing/CMakeLists.txt @@ -7,6 +7,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index bfc4e8db6b..21d3bcb5d3 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -31,6 +31,7 @@ endif() install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 8e73a17709..74149b6552 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -17,7 +17,8 @@ target_link_libraries(collision_detector_fcl_plugin ${catkin_LIBRARIES} ${MOVEIT install(TARGETS ${MOVEIT_LIB_NAME} collision_detector_fcl_plugin LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index 491b47f0e8..ad1850a61e 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -30,7 +30,7 @@ endif() install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/constraint_samplers/CMakeLists.txt b/moveit_core/constraint_samplers/CMakeLists.txt index e988eb2108..958e37b563 100644 --- a/moveit_core/constraint_samplers/CMakeLists.txt +++ b/moveit_core/constraint_samplers/CMakeLists.txt @@ -19,7 +19,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/distance_field/CMakeLists.txt b/moveit_core/distance_field/CMakeLists.txt index ac60b52783..3955c94fd3 100644 --- a/moveit_core/distance_field/CMakeLists.txt +++ b/moveit_core/distance_field/CMakeLists.txt @@ -12,7 +12,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/dynamics_solver/CMakeLists.txt b/moveit_core/dynamics_solver/CMakeLists.txt index 61324a752d..07028fc9e5 100644 --- a/moveit_core/dynamics_solver/CMakeLists.txt +++ b/moveit_core/dynamics_solver/CMakeLists.txt @@ -8,6 +8,7 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/exceptions/CMakeLists.txt b/moveit_core/exceptions/CMakeLists.txt index 6b80cf3c28..70ab423d27 100644 --- a/moveit_core/exceptions/CMakeLists.txt +++ b/moveit_core/exceptions/CMakeLists.txt @@ -7,5 +7,6 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/kinematic_constraints/CMakeLists.txt b/moveit_core/kinematic_constraints/CMakeLists.txt index ea45aa72f0..18ff796f70 100644 --- a/moveit_core/kinematic_constraints/CMakeLists.txt +++ b/moveit_core/kinematic_constraints/CMakeLists.txt @@ -12,7 +12,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/kinematics_base/CMakeLists.txt b/moveit_core/kinematics_base/CMakeLists.txt index f4d98357ef..2ec7a736f4 100644 --- a/moveit_core/kinematics_base/CMakeLists.txt +++ b/moveit_core/kinematics_base/CMakeLists.txt @@ -13,6 +13,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/kinematics_metrics/CMakeLists.txt b/moveit_core/kinematics_metrics/CMakeLists.txt index 8438c8641d..6a43296df8 100644 --- a/moveit_core/kinematics_metrics/CMakeLists.txt +++ b/moveit_core/kinematics_metrics/CMakeLists.txt @@ -8,6 +8,7 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/planning_interface/CMakeLists.txt b/moveit_core/planning_interface/CMakeLists.txt index 33c0e1a789..8a876192b5 100644 --- a/moveit_core/planning_interface/CMakeLists.txt +++ b/moveit_core/planning_interface/CMakeLists.txt @@ -11,6 +11,7 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/planning_request_adapter/CMakeLists.txt b/moveit_core/planning_request_adapter/CMakeLists.txt index 87038c1d31..401e955ded 100644 --- a/moveit_core/planning_request_adapter/CMakeLists.txt +++ b/moveit_core/planning_request_adapter/CMakeLists.txt @@ -8,6 +8,7 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/planning_scene/CMakeLists.txt b/moveit_core/planning_scene/CMakeLists.txt index 13174d3f1d..cfa146e3ec 100644 --- a/moveit_core/planning_scene/CMakeLists.txt +++ b/moveit_core/planning_scene/CMakeLists.txt @@ -18,7 +18,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) if(CATKIN_ENABLE_TESTING) diff --git a/moveit_core/profiler/CMakeLists.txt b/moveit_core/profiler/CMakeLists.txt index 92671fd8cd..803b7ebdb8 100644 --- a/moveit_core/profiler/CMakeLists.txt +++ b/moveit_core/profiler/CMakeLists.txt @@ -7,5 +7,6 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${urdfdom_LIBRARIES install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/robot_model/CMakeLists.txt b/moveit_core/robot_model/CMakeLists.txt index a3383680b3..40a6199da4 100644 --- a/moveit_core/robot_model/CMakeLists.txt +++ b/moveit_core/robot_model/CMakeLists.txt @@ -27,5 +27,6 @@ endif() install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/robot_state/CMakeLists.txt b/moveit_core/robot_state/CMakeLists.txt index d2cffe5f6c..90b30c9db7 100644 --- a/moveit_core/robot_state/CMakeLists.txt +++ b/moveit_core/robot_state/CMakeLists.txt @@ -19,7 +19,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) # Unit tests diff --git a/moveit_core/robot_trajectory/CMakeLists.txt b/moveit_core/robot_trajectory/CMakeLists.txt index 9bcfe4ae86..29b89e5aa2 100644 --- a/moveit_core/robot_trajectory/CMakeLists.txt +++ b/moveit_core/robot_trajectory/CMakeLists.txt @@ -8,6 +8,7 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/trajectory_processing/CMakeLists.txt b/moveit_core/trajectory_processing/CMakeLists.txt index fdd392a586..7c51bfbec5 100644 --- a/moveit_core/trajectory_processing/CMakeLists.txt +++ b/moveit_core/trajectory_processing/CMakeLists.txt @@ -13,7 +13,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_core/transforms/CMakeLists.txt b/moveit_core/transforms/CMakeLists.txt index 411b925a68..ac2bd777b3 100644 --- a/moveit_core/transforms/CMakeLists.txt +++ b/moveit_core/transforms/CMakeLists.txt @@ -8,7 +8,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) # Unit tests diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt index 05f4bb4878..9ea399702a 100644 --- a/moveit_core/utils/CMakeLists.txt +++ b/moveit_core/utils/CMakeLists.txt @@ -22,6 +22,7 @@ install( ${MOVEIT_LIB_NAME} ${MOVEIT_TEST_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt index d22d017782..6dcd3680b0 100644 --- a/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt +++ b/moveit_experimental/kinematics_cache/v2/kinematics_cache/CMakeLists.txt @@ -9,6 +9,9 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) target_link_libraries(${MOVEIT_LIB_NAME} moveit_robot_model ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt index 8aaa5b86dc..12d18cecef 100644 --- a/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt +++ b/moveit_experimental/kinematics_constraint_aware/CMakeLists.txt @@ -7,5 +7,8 @@ add_dependencies(${MOVEIT_LIB_NAME} ${catkin_EXPORTED_TARGETS}) target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt index 05005fa6a5..b295d3eb50 100644 --- a/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/cached_ik_kinematics_plugin/CMakeLists.txt @@ -9,7 +9,10 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} ${Boost_FILESYSTEM_LIBRARY} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) if(trac_ik_kinematics_plugin_FOUND) include_directories(${trac_ik_kinematics_plugin_INCLUDE_DIRS}) @@ -27,7 +30,10 @@ if(trac_ik_kinematics_plugin_FOUND) target_link_libraries(${MOVEIT_LIB_NAME} ${trac_ik_kinematics_plugin_LIBRARIES}) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_DEFINITIONS "CACHED_IK_KINEMATICS_TRAC_IK") endif() -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) # This is just for testing purposes; the arms from Universal Robots have # analytic solvers, so caching just adds extra overhead. @@ -42,7 +48,10 @@ if(ur_kinematics_FOUND) moveit_cached_ik_kinematics_base ${ur${UR}_pluginlib} ${catkin_LIBRARIES}) - install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) endforeach() endif() diff --git a/moveit_kinematics/ikfast_kinematics_plugin/templates/CMakeLists.txt b/moveit_kinematics/ikfast_kinematics_plugin/templates/CMakeLists.txt index de49b96da2..e4020ed280 100644 --- a/moveit_kinematics/ikfast_kinematics_plugin/templates/CMakeLists.txt +++ b/moveit_kinematics/ikfast_kinematics_plugin/templates/CMakeLists.txt @@ -26,7 +26,9 @@ target_compile_options(${IKFAST_LIBRARY_NAME} PRIVATE -Wno-unused-variable) install(TARGETS ${IKFAST_LIBRARY_NAME} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install( FILES diff --git a/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt index 9388ae6f26..cd3ffc0891 100644 --- a/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/kdl_kinematics_plugin/CMakeLists.txt @@ -7,5 +7,8 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt index 0397388312..1dadddcd56 100644 --- a/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/lma_kinematics_plugin/CMakeLists.txt @@ -5,5 +5,8 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt b/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt index b7829f2412..2cf14dd877 100644 --- a/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt +++ b/moveit_kinematics/srv_kinematics_plugin/CMakeLists.txt @@ -5,5 +5,8 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_kinematics/test/CMakeLists.txt b/moveit_kinematics/test/CMakeLists.txt index b7dee1f18d..be739327c6 100644 --- a/moveit_kinematics/test/CMakeLists.txt +++ b/moveit_kinematics/test/CMakeLists.txt @@ -36,5 +36,6 @@ if(CATKIN_ENABLE_TESTING) target_link_libraries(benchmark_ik ${catkin_LIBRARIES} ${moveit_ros_planning_LIBRARIES} ${Boost_PROGRAM_OPTIONS_LIBRARY}) - install(TARGETS benchmark_ik DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + install(TARGETS benchmark_ik + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) endif() diff --git a/moveit_planners/chomp/chomp_interface/CMakeLists.txt b/moveit_planners/chomp/chomp_interface/CMakeLists.txt index 3e03d56474..a811145448 100644 --- a/moveit_planners/chomp/chomp_interface/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_interface/CMakeLists.txt @@ -54,7 +54,7 @@ install(DIRECTORY include/chomp_interface/ install(TARGETS ${PROJECT_NAME} chomp_planner_plugin ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) if(CATKIN_ENABLE_TESTING) diff --git a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt index 69655a2c84..d02a10255a 100644 --- a/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_motion_planner/CMakeLists.txt @@ -34,5 +34,5 @@ install(DIRECTORY include/${PROJECT_NAME}/ install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) diff --git a/moveit_planners/chomp/chomp_optimizer_adapter/CMakeLists.txt b/moveit_planners/chomp/chomp_optimizer_adapter/CMakeLists.txt index 91d6b6a455..0e69e70585 100644 --- a/moveit_planners/chomp/chomp_optimizer_adapter/CMakeLists.txt +++ b/moveit_planners/chomp/chomp_optimizer_adapter/CMakeLists.txt @@ -24,5 +24,5 @@ install(FILES chomp_optimizer_adapter_plugin_description.xml install(TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) diff --git a/moveit_planners/ompl/ompl_interface/CMakeLists.txt b/moveit_planners/ompl/ompl_interface/CMakeLists.txt index cc9181efee..0f7c18bbb9 100644 --- a/moveit_planners/ompl/ompl_interface/CMakeLists.txt +++ b/moveit_planners/ompl/ompl_interface/CMakeLists.txt @@ -40,8 +40,11 @@ add_library(moveit_ompl_planner_plugin src/ompl_planner_manager.cpp) set_target_properties(moveit_ompl_planner_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(moveit_ompl_planner_plugin ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} moveit_ompl_planner moveit_ompl_planner_plugin moveit_generate_state_database +install(TARGETS ${MOVEIT_LIB_NAME} moveit_ompl_planner_plugin LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) +install(TARGETS moveit_ompl_planner moveit_generate_state_database RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_plugins/moveit_fake_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_fake_controller_manager/CMakeLists.txt index d0e7a81bfe..7a24177c77 100644 --- a/moveit_plugins/moveit_fake_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_fake_controller_manager/CMakeLists.txt @@ -32,7 +32,10 @@ add_library(${PROJECT_NAME} set_target_properties(${PROJECT_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${PROJECT_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(FILES moveit_fake_controller_manager_plugin_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} diff --git a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt index 8b61d3b039..c590d3de6d 100644 --- a/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt +++ b/moveit_plugins/moveit_ros_control_interface/CMakeLists.txt @@ -69,7 +69,7 @@ target_link_libraries(${PROJECT_NAME}_trajectory_plugin install(TARGETS ${PROJECT_NAME}_plugin ${PROJECT_NAME}_trajectory_plugin ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} -RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} ) ## Mark cpp header files for installation diff --git a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt index ec00ba8601..48c02ea8b5 100644 --- a/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt +++ b/moveit_plugins/moveit_simple_controller_manager/CMakeLists.txt @@ -33,7 +33,10 @@ add_library(${PROJECT_NAME} set_target_properties(${PROJECT_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${PROJECT_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${PROJECT_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(FILES moveit_simple_controller_manager_plugin_description.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index 1b41bfcd22..2463628a58 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -43,8 +43,14 @@ target_link_libraries(moveit_run_benchmark ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES install( TARGETS - ${MOVEIT_LIB_NAME} moveit_run_benchmark + ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +install( + TARGETS + moveit_run_benchmark RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt b/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt index 8cdfecab66..036197fc58 100644 --- a/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt +++ b/moveit_ros/manipulation/move_group_pick_place_capability/CMakeLists.txt @@ -11,6 +11,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} moveit_pick_place_planner ${catkin_LIBR install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/manipulation/pick_place/CMakeLists.txt b/moveit_ros/manipulation/pick_place/CMakeLists.txt index 4e41c8a4e5..fb371ae640 100644 --- a/moveit_ros/manipulation/pick_place/CMakeLists.txt +++ b/moveit_ros/manipulation/pick_place/CMakeLists.txt @@ -14,5 +14,8 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/move_group/CMakeLists.txt b/moveit_ros/move_group/CMakeLists.txt index 82578d5bf4..783f29faa7 100644 --- a/moveit_ros/move_group/CMakeLists.txt +++ b/moveit_ros/move_group/CMakeLists.txt @@ -67,10 +67,13 @@ target_link_libraries(move_group moveit_move_group_capabilities_base ${catkin_LI target_link_libraries(moveit_move_group_default_capabilities moveit_move_group_capabilities_base ${catkin_LIBRARIES} ${Boost_LIBRARIES}) target_link_libraries(list_move_group_capabilities ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS move_group list_move_group_capabilities moveit_move_group_capabilities_base moveit_move_group_default_capabilities +install(TARGETS move_group list_move_group_capabilities + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(TARGETS moveit_move_group_capabilities_base moveit_move_group_default_capabilities ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/occupancy_map_monitor/CMakeLists.txt b/moveit_ros/occupancy_map_monitor/CMakeLists.txt index 56305e5bde..bdb0bae0f1 100644 --- a/moveit_ros/occupancy_map_monitor/CMakeLists.txt +++ b/moveit_ros/occupancy_map_monitor/CMakeLists.txt @@ -56,8 +56,13 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_executable(moveit_ros_occupancy_map_server src/occupancy_map_server.cpp) target_link_libraries(moveit_ros_occupancy_map_server ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} moveit_ros_occupancy_map_server - LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION} +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +) + +install(TARGETS moveit_ros_occupancy_map_server RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt index 81485c633d..4222cd346a 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt +++ b/moveit_ros/perception/depth_image_octomap_updater/CMakeLists.txt @@ -10,5 +10,8 @@ add_library(${MOVEIT_LIB_NAME} src/updater_plugin.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt index ce935b1f36..e9092875c1 100644 --- a/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt +++ b/moveit_ros/perception/lazy_free_space_updater/CMakeLists.txt @@ -8,5 +8,8 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_dependencies(${MOVEIT_LIB_NAME} ${sensor_msgs_EXPORTED_TARGETS}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/perception/mesh_filter/CMakeLists.txt b/moveit_ros/perception/mesh_filter/CMakeLists.txt index 940772f8da..f08902a474 100644 --- a/moveit_ros/perception/mesh_filter/CMakeLists.txt +++ b/moveit_ros/perception/mesh_filter/CMakeLists.txt @@ -22,5 +22,8 @@ if (CATKIN_ENABLE_TESTING) endif() endif() -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/perception/point_containment_filter/CMakeLists.txt b/moveit_ros/perception/point_containment_filter/CMakeLists.txt index ed76980c0a..a672692acb 100644 --- a/moveit_ros/perception/point_containment_filter/CMakeLists.txt +++ b/moveit_ros/perception/point_containment_filter/CMakeLists.txt @@ -6,5 +6,8 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES COMPILE_FLAGS "${CMAKE_CXX_F set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES LINK_FLAGS "${OpenMP_CXX_FLAGS}") target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt b/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt index 503c46fb2f..425a12beed 100644 --- a/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt +++ b/moveit_ros/perception/pointcloud_octomap_updater/CMakeLists.txt @@ -14,4 +14,5 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/perception/semantic_world/CMakeLists.txt b/moveit_ros/perception/semantic_world/CMakeLists.txt index 6ed3c99610..0c6ef4f3f0 100644 --- a/moveit_ros/perception/semantic_world/CMakeLists.txt +++ b/moveit_ros/perception/semantic_world/CMakeLists.txt @@ -9,4 +9,5 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt b/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt index 86eea90717..6ad2115652 100644 --- a/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/collision_plugin_loader/CMakeLists.txt @@ -4,5 +4,8 @@ add_library(${MOVEIT_LIB_NAME} src/collision_plugin_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt b/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt index 8e0dd2dc28..8e11bfaafa 100644 --- a/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt +++ b/moveit_ros/planning/constraint_sampler_manager_loader/CMakeLists.txt @@ -4,5 +4,8 @@ add_library(${MOVEIT_LIB_NAME} src/constraint_sampler_manager_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt index ebcc035b60..48ce472264 100644 --- a/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt +++ b/moveit_ros/planning/kinematics_plugin_loader/CMakeLists.txt @@ -4,5 +4,8 @@ add_library(${MOVEIT_LIB_NAME} src/kinematics_plugin_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_rdf_loader ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/plan_execution/CMakeLists.txt b/moveit_ros/planning/plan_execution/CMakeLists.txt index 6d2a0c24fe..6b579cfb11 100644 --- a/moveit_ros/planning/plan_execution/CMakeLists.txt +++ b/moveit_ros/planning/plan_execution/CMakeLists.txt @@ -11,5 +11,8 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES} ) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/planning_pipeline/CMakeLists.txt b/moveit_ros/planning/planning_pipeline/CMakeLists.txt index 853d2efb11..abeb034e3a 100644 --- a/moveit_ros/planning/planning_pipeline/CMakeLists.txt +++ b/moveit_ros/planning/planning_pipeline/CMakeLists.txt @@ -4,5 +4,8 @@ add_library(${MOVEIT_LIB_NAME} src/planning_pipeline.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt b/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt index f3a9dbae8d..b32ffe5349 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt +++ b/moveit_ros/planning/planning_request_adapter_plugins/CMakeLists.txt @@ -19,6 +19,10 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_executable(moveit_list_request_adapter_plugins src/list.cpp) target_link_libraries(moveit_list_request_adapter_plugins ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} moveit_list_request_adapter_plugins +install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +install(TARGETS moveit_list_request_adapter_plugins RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) diff --git a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt index 9ad23d6175..6329feef36 100644 --- a/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt +++ b/moveit_ros/planning/planning_scene_monitor/CMakeLists.txt @@ -14,5 +14,8 @@ target_link_libraries(${MOVEIT_LIB_NAME} add_executable(demo_scene demos/demo_scene.cpp) target_link_libraries(demo_scene ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/rdf_loader/CMakeLists.txt b/moveit_ros/planning/rdf_loader/CMakeLists.txt index 0a0dbe5055..0b91cafd81 100644 --- a/moveit_ros/planning/rdf_loader/CMakeLists.txt +++ b/moveit_ros/planning/rdf_loader/CMakeLists.txt @@ -4,5 +4,8 @@ add_library(${MOVEIT_LIB_NAME} src/rdf_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/robot_model_loader/CMakeLists.txt b/moveit_ros/planning/robot_model_loader/CMakeLists.txt index 13af8cdd78..9790d1bcc3 100644 --- a/moveit_ros/planning/robot_model_loader/CMakeLists.txt +++ b/moveit_ros/planning/robot_model_loader/CMakeLists.txt @@ -8,5 +8,8 @@ add_library(${MOVEIT_LIB_NAME} src/robot_model_loader.cpp) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} moveit_rdf_loader moveit_kinematics_plugin_loader ${catkin_LIBRARIES}) -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt index 51b7336ac1..14a2c23be8 100644 --- a/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt +++ b/moveit_ros/planning/trajectory_execution_manager/CMakeLists.txt @@ -5,7 +5,10 @@ set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_V target_link_libraries(${MOVEIT_LIB_NAME} moveit_planning_scene_monitor moveit_robot_model_loader ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_dependencies(${MOVEIT_LIB_NAME} ${moveit_ros_planning_EXPORTED_TARGETS}) # don't build until necessary msgs are finish -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) add_library(test_controller_manager_plugin test/test_moveit_controller_manager_plugin.cpp) diff --git a/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt b/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt index f5b6953406..71b61285a4 100644 --- a/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt +++ b/moveit_ros/planning_interface/common_planning_interface_objects/CMakeLists.txt @@ -6,6 +6,7 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${PYTHON_LIBRARIES} install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index eacfa2aecb..6ff6444e7a 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -14,11 +14,13 @@ set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECT install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME}_python ARCHIVE DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt b/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt index 7658b2583e..11489f296c 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt @@ -12,10 +12,10 @@ set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECT install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME}_python - ARCHIVE DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt b/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt index 6d1e6899a6..1f3cb1c93b 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt +++ b/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt @@ -6,7 +6,8 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES} install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) add_library(${MOVEIT_LIB_NAME}_python src/wrap_python_roscpp_initializer.cpp) target_link_libraries(${MOVEIT_LIB_NAME}_python ${MOVEIT_LIB_NAME} ${PYTHON_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) @@ -15,7 +16,6 @@ set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_r set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") install(TARGETS ${MOVEIT_LIB_NAME}_python - ARCHIVE DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_ros/planning_interface/robot_interface/CMakeLists.txt b/moveit_ros/planning_interface/robot_interface/CMakeLists.txt index 56cb7b4098..0c6a4a22bf 100644 --- a/moveit_ros/planning_interface/robot_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/robot_interface/CMakeLists.txt @@ -8,5 +8,4 @@ set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_r set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") install(TARGETS ${MOVEIT_LIB_NAME}_python - ARCHIVE DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) + DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) diff --git a/moveit_ros/robot_interaction/CMakeLists.txt b/moveit_ros/robot_interaction/CMakeLists.txt index 8050ff8d75..d18735a809 100644 --- a/moveit_ros/robot_interaction/CMakeLists.txt +++ b/moveit_ros/robot_interaction/CMakeLists.txt @@ -54,7 +54,10 @@ if (CATKIN_ENABLE_TESTING) ${Boost_LIBRARIES}) endif() -install(TARGETS ${MOVEIT_LIB_NAME} LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION}) +install(TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(DIRECTORY resources DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt index 41c9b07b59..6f4ce1f245 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/CMakeLists.txt @@ -36,4 +36,5 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt index 77a06066ac..109bb569f6 100644 --- a/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/planning_scene_rviz_plugin/CMakeLists.txt @@ -14,4 +14,5 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt index 6a4d92f2f7..8db0bf29fc 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/robot_state_rviz_plugin/CMakeLists.txt @@ -15,5 +15,6 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME}_core ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt index 9baca76cfb..a9769d25d1 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt +++ b/moveit_ros/visualization/rviz_plugin_render_tools/CMakeLists.txt @@ -35,4 +35,5 @@ install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt index 081058868c..97b09ca864 100644 --- a/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt +++ b/moveit_ros/visualization/trajectory_rviz_plugin/CMakeLists.txt @@ -27,5 +27,6 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core ${catkin_LIBRAR install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(TARGETS ${MOVEIT_LIB_NAME} ${MOVEIT_LIB_NAME}_core + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/warehouse/warehouse/CMakeLists.txt b/moveit_ros/warehouse/warehouse/CMakeLists.txt index 2a459f97c0..5f1b0e000c 100644 --- a/moveit_ros/warehouse/warehouse/CMakeLists.txt +++ b/moveit_ros/warehouse/warehouse/CMakeLists.txt @@ -32,12 +32,17 @@ target_link_libraries(moveit_warehouse_services ${catkin_LIBRARIES} ${MOVEIT_LIB install( TARGETS ${MOVEIT_LIB_NAME} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + +install( + TARGETS moveit_save_to_warehouse moveit_warehouse_broadcast moveit_warehouse_import_from_text moveit_warehouse_save_as_text moveit_init_demo_warehouse moveit_warehouse_services - LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) diff --git a/moveit_setup_assistant/CMakeLists.txt b/moveit_setup_assistant/CMakeLists.txt index fa15457b8b..f01787d422 100644 --- a/moveit_setup_assistant/CMakeLists.txt +++ b/moveit_setup_assistant/CMakeLists.txt @@ -141,9 +141,14 @@ set_target_properties(${PROJECT_NAME}_updater PROPERTIES OUTPUT_NAME collisions_updater PREFIX "") -install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_widgets ${PROJECT_NAME}_tools ${PROJECT_NAME}_updater - LIBRARY DESTINATION ${CATKIN_GLOBAL_LIB_DESTINATION} +install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_updater RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(TARGETS ${PROJECT_NAME}_widgets ${PROJECT_NAME}_tools + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) + install(DIRECTORY include/ DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}) install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) From 889447f2dfe6bb997f7a32dd61069008018b0ec8 Mon Sep 17 00:00:00 2001 From: Dave Coleman Date: Tue, 13 Aug 2019 13:41:37 -0600 Subject: [PATCH 27/96] Remove packages without Jenkins badges (#1617) --- README.md | 3 --- 1 file changed, 3 deletions(-) diff --git a/README.md b/README.md index 8de31d4900..0b330cc1bc 100644 --- a/README.md +++ b/README.md @@ -39,7 +39,6 @@ build farm | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kdev__mo MoveIt Package | Kinetic Source | Kinetic Debian | Melodic Source | Melodic Debian --------------- | -------------- | -------------- | -------------- | -------------- moveit | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit__ubuntu_bionic_amd64__binary) -moveit_base | | | | moveit_chomp_optimizer_adapter | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_chomp_optimizer_adapter__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_chomp_optimizer_adapter__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_chomp_optimizer_adapter__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_chomp_optimizer_adapter__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_chomp_optimizer_adapter__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_chomp_optimizer_adapter__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_chomp_optimizer_adapter__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_chomp_optimizer_adapter__ubuntu_bionic_amd64__binary) moveit_commander | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_commander__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_commander__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_commander__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_commander__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_commander__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_commander__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_commander__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_commander__ubuntu_bionic_amd64__binary) moveit_core | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_core__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_core__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_core__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_core__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_core__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_core__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_core__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_core__ubuntu_bionic_amd64__binary) @@ -57,7 +56,6 @@ moveit_ros_benchmarks | [![Build Status](http://build.ros.org/buildStatus/icon?j moveit_ros_control_interface | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_control_interface__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_control_interface__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_control_interface__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_control_interface__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_control_interface__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_control_interface__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_control_interface__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_control_interface__ubuntu_bionic_amd64__binary) moveit_ros_manipulation | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_manipulation__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_manipulation__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_manipulation__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_manipulation__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_manipulation__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_manipulation__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_manipulation__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_manipulation__ubuntu_bionic_amd64__binary) moveit_ros_move_group | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_move_group__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_move_group__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_move_group__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_move_group__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_move_group__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_move_group__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_move_group__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_move_group__ubuntu_bionic_amd64__binary) -moveit_ros_occupancy_map_monitor | | | | moveit_ros_perception | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_perception__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_perception__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_perception__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_perception__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_perception__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_perception__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_perception__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_perception__ubuntu_bionic_amd64__binary) moveit_ros_planning | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_planning__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_planning__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_planning__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_planning__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_planning__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_planning__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_planning__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_planning__ubuntu_bionic_amd64__binary) moveit_ros_planning_interface | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_ros_planning_interface__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_ros_planning_interface__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_ros_planning_interface__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_ros_planning_interface__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_ros_planning_interface__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_ros_planning_interface__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_ros_planning_interface__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_ros_planning_interface__ubuntu_bionic_amd64__binary) @@ -67,7 +65,6 @@ moveit_ros_warehouse | [![Build Status](http://build.ros.org/buildStatus/icon?jo moveit_runtime | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_runtime__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_runtime__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_runtime__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_runtime__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_runtime__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_runtime__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_runtime__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_runtime__ubuntu_bionic_amd64__binary) moveit_setup_assistant | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_setup_assistant__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_setup_assistant__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_setup_assistant__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_setup_assistant__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_setup_assistant__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_setup_assistant__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_setup_assistant__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_setup_assistant__ubuntu_bionic_amd64__binary) moveit_simple_controller_manager | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_simple_controller_manager__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_simple_controller_manager__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_simple_controller_manager__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_simple_controller_manager__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_simple_controller_manager__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_simple_controller_manager__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_simple_controller_manager__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_simple_controller_manager__ubuntu_bionic_amd64__binary) -moveit_tutorials | | | | moveit_visual_tools | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__moveit_visual_tools__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__moveit_visual_tools__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__moveit_visual_tools__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__moveit_visual_tools__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__moveit_visual_tools__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__moveit_visual_tools__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__moveit_visual_tools__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__moveit_visual_tools__ubuntu_bionic_amd64__binary) chomp_motion_planner | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__chomp_motion_planner__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__chomp_motion_planner__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__chomp_motion_planner__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__chomp_motion_planner__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__chomp_motion_planner__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__chomp_motion_planner__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__chomp_motion_planner__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__chomp_motion_planner__ubuntu_bionic_amd64__binary) geometric_shapes | [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__geometric_shapes__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__geometric_shapes__ubuntu_xenial__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__geometric_shapes__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__geometric_shapes__ubuntu_xenial_amd64__binary) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__geometric_shapes__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__geometric_shapes__ubuntu_bionic__source) | [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__geometric_shapes__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__geometric_shapes__ubuntu_bionic_amd64__binary) From eae8f02070fd05ea4c53b476624a469eea7ca362 Mon Sep 17 00:00:00 2001 From: Jonathan Binney Date: Tue, 13 Aug 2019 21:31:22 -0700 Subject: [PATCH 28/96] Use standard cmake text for metapackages (#1620) --- moveit/CMakeLists.txt | 2 +- moveit_planners/moveit_planners/CMakeLists.txt | 2 +- moveit_plugins/moveit_plugins/CMakeLists.txt | 2 +- moveit_ros/moveit_ros/CMakeLists.txt | 2 +- moveit_runtime/CMakeLists.txt | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) diff --git a/moveit/CMakeLists.txt b/moveit/CMakeLists.txt index 9acc0a9b9e..9d8f3239d4 100644 --- a/moveit/CMakeLists.txt +++ b/moveit/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 2.8.3) project(moveit) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/moveit_planners/moveit_planners/CMakeLists.txt b/moveit_planners/moveit_planners/CMakeLists.txt index 753bb7b4d9..e6e2b34540 100644 --- a/moveit_planners/moveit_planners/CMakeLists.txt +++ b/moveit_planners/moveit_planners/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 2.8.3) project(moveit_planners) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/moveit_plugins/moveit_plugins/CMakeLists.txt b/moveit_plugins/moveit_plugins/CMakeLists.txt index 9afdc1d9d8..03c972ba5f 100644 --- a/moveit_plugins/moveit_plugins/CMakeLists.txt +++ b/moveit_plugins/moveit_plugins/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 2.8.3) project(moveit_plugins) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/moveit_ros/moveit_ros/CMakeLists.txt b/moveit_ros/moveit_ros/CMakeLists.txt index 5425d0c2e5..75cf534418 100644 --- a/moveit_ros/moveit_ros/CMakeLists.txt +++ b/moveit_ros/moveit_ros/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 2.8.3) project(moveit_ros) find_package(catkin REQUIRED) catkin_metapackage() diff --git a/moveit_runtime/CMakeLists.txt b/moveit_runtime/CMakeLists.txt index 0224cde26c..18700d6157 100644 --- a/moveit_runtime/CMakeLists.txt +++ b/moveit_runtime/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.1.3) +cmake_minimum_required(VERSION 2.8.3) project(moveit_runtime) find_package(catkin REQUIRED) catkin_metapackage() From d7e0dfde20cd9c601190aca1f20db71b5a898255 Mon Sep 17 00:00:00 2001 From: Jafar Abdi Date: Wed, 14 Aug 2019 09:17:13 +0300 Subject: [PATCH 29/96] Use QDir::currentPath() rather than getenv("PWD") (#1618) --- .../src/widgets/setup_assistant_widget.cpp | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp index a2b1a1fb07..511463a968 100644 --- a/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp +++ b/moveit_setup_assistant/src/widgets/setup_assistant_widget.cpp @@ -47,6 +47,7 @@ #include #include #include +#include #include // for loading all avail kinematic planners // Rviz #include @@ -113,13 +114,7 @@ SetupAssistantWidget::SetupAssistantWidget(QWidget* parent, const boost::program } else { - // Open the directory where the MSA was started from. - // cf. http://stackoverflow.com/a/7413516/577001 - QString pwdir(""); - char* pwd; - pwd = getenv("PWD"); - pwdir.append(pwd); - start_screen_widget_->stack_path_->setPath(pwdir); + start_screen_widget_->stack_path_->setPath(QDir::currentPath()); } // Add Navigation Buttons (but do not load widgets yet except start screen) From f231ad7155090720ccaab265607e19f5fb2c7fc8 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Wed, 14 Aug 2019 00:29:46 -0700 Subject: [PATCH 30/96] remove GCC extension and alternative operator usage. (#1583) replace the gcc extension and alternative operator usage Also guard use of Linux-specific abi header --- .../planning_request_adapter.h | 8 +++++++- moveit_core/robot_state/src/robot_state.cpp | 2 +- moveit_core/utils/src/robot_model_test_utils.cpp | 14 +++++++------- .../chomp_motion_planner/src/chomp_trajectory.cpp | 2 +- .../src/current_state_monitor.cpp | 10 +++++----- 5 files changed, 21 insertions(+), 15 deletions(-) diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index fd2b34a424..9c11302a02 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -40,7 +40,9 @@ #include #include #include +#if !defined(_MSC_VER) #include +#endif /** \brief Generic interface to adapting motion planning requests */ namespace planning_request_adapter @@ -70,8 +72,12 @@ class PlanningRequestAdapter // Get name of derived adapter std::string adapter_name = typeid(*this).name(); // Try to demangle the name - int status; + int status = 1; +#if defined(_MSC_VER) + std::string demangled_name = adapter_name; +#else std::string demangled_name = abi::__cxa_demangle(adapter_name.c_str(), NULL, NULL, &status); +#endif if (status == 0) adapter_name = demangled_name; ROS_WARN_NAMED("planning_request_adapter", "Implementation of function initialize() is missing from '%s'." diff --git a/moveit_core/robot_state/src/robot_state.cpp b/moveit_core/robot_state/src/robot_state.cpp index 756ba3a97c..abf7034f98 100644 --- a/moveit_core/robot_state/src/robot_state.cpp +++ b/moveit_core/robot_state/src/robot_state.cpp @@ -1232,7 +1232,7 @@ bool RobotState::getJacobian(const JointModelGroup* group, const LinkModel* link const JointModel* pjm = link->getParentJointModel(); if (pjm->getVariableCount() > 0) { - if (not group->hasJointModel(pjm->getName())) + if (!group->hasJointModel(pjm->getName())) { link = pjm->getParentLinkModel(); continue; diff --git a/moveit_core/utils/src/robot_model_test_utils.cpp b/moveit_core/utils/src/robot_model_test_utils.cpp index 50221182ec..e8bf5d3407 100644 --- a/moveit_core/utils/src/robot_model_test_utils.cpp +++ b/moveit_core/utils/src/robot_model_test_utils.cpp @@ -120,14 +120,14 @@ void RobotModelBuilder::addChain(const std::string& section, const std::string& return; } // First link should already be added. - if (not urdf_model_->getLink(link_names[0])) + if (!urdf_model_->getLink(link_names[0])) { ROS_ERROR_NAMED(LOGNAME, "Link %s not present in builder yet!", link_names[0].c_str()); is_valid_ = false; return; } - if (not joint_origins.empty() && link_names.size() - 1 != joint_origins.size()) + if (!joint_origins.empty() && link_names.size() - 1 != joint_origins.size()) { ROS_ERROR_NAMED(LOGNAME, "There should be one more link (%zu) than there are joint origins (%zu)", link_names.size(), joint_origins.size()); @@ -152,7 +152,7 @@ void RobotModelBuilder::addChain(const std::string& section, const std::string& joint->name = link_names[i - 1] + "-" + link_names[i] + "-joint"; // Default to Identity transform for origins. joint->parent_to_joint_origin_transform.clear(); - if (not joint_origins.empty()) + if (!joint_origins.empty()) { geometry_msgs::Pose o = joint_origins[i - 1]; joint->parent_to_joint_origin_transform.position = urdf::Vector3(o.position.x, o.position.y, o.position.z); @@ -197,7 +197,7 @@ void RobotModelBuilder::addChain(const std::string& section, const std::string& void RobotModelBuilder::addInertial(const std::string& link_name, double mass, geometry_msgs::Pose origin, double ixx, double ixy, double ixz, double iyy, double iyz, double izz) { - if (not urdf_model_->getLink(link_name)) + if (!urdf_model_->getLink(link_name)) { ROS_ERROR_NAMED(LOGNAME, "Link %s not present in builder yet!", link_name.c_str()); is_valid_ = false; @@ -260,7 +260,7 @@ void RobotModelBuilder::addCollisionMesh(const std::string& link_name, const std void RobotModelBuilder::addLinkCollision(const std::string& link_name, const urdf::CollisionSharedPtr& collision, geometry_msgs::Pose origin) { - if (not urdf_model_->getLink(link_name)) + if (!urdf_model_->getLink(link_name)) { ROS_ERROR_NAMED(LOGNAME, "Link %s not present in builder yet!", link_name.c_str()); is_valid_ = false; @@ -278,7 +278,7 @@ void RobotModelBuilder::addLinkCollision(const std::string& link_name, const urd void RobotModelBuilder::addLinkVisual(const std::string& link_name, const urdf::VisualSharedPtr& vis, geometry_msgs::Pose origin) { - if (not urdf_model_->getLink(link_name)) + if (!urdf_model_->getLink(link_name)) { ROS_ERROR_NAMED(LOGNAME, "Link %s not present in builder yet!", link_name.c_str()); is_valid_ = false; @@ -290,7 +290,7 @@ void RobotModelBuilder::addLinkVisual(const std::string& link_name, const urdf:: urdf::LinkSharedPtr link; urdf_model_->getLink(link_name, link); - if (not link->visual_array.empty()) + if (!link->visual_array.empty()) { link->visual_array.push_back(vis); } diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp index 8580682a20..e1f56aa0e7 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_trajectory.cpp @@ -155,7 +155,7 @@ void ChompTrajectory::fillInMinJerk() // calculate the spline coefficients for each joint: // (these are for the special case of zero start and end vel and acc) - double coeff[num_joints_][6]; + std::vector coeff(num_joints_); for (size_t i = 0; i < num_joints_; i++) { double x0 = (*this)(start_index, i); diff --git a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp index 43f1da2158..64ae7465d2 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/current_state_monitor.cpp @@ -443,20 +443,20 @@ void planning_scene_monitor::CurrentStateMonitor::tfCallback() continue; joint_time_[joint] = latest_common_time; - double new_values[joint->getStateSpaceDimension()]; + std::vector new_values(joint->getStateSpaceDimension()); const robot_model::LinkModel* link = joint->getChildLinkModel(); if (link->jointOriginTransformIsIdentity()) - joint->computeVariablePositions(tf2::transformToEigen(transf), new_values); + joint->computeVariablePositions(tf2::transformToEigen(transf), new_values.data()); else joint->computeVariablePositions(link->getJointOriginTransform().inverse() * tf2::transformToEigen(transf), - new_values); + new_values.data()); - if (joint->distance(new_values, robot_state_.getJointPositions(joint)) > 1e-5) + if (joint->distance(new_values.data(), robot_state_.getJointPositions(joint)) > 1e-5) { changes = true; } - robot_state_.setJointPositions(joint, new_values); + robot_state_.setJointPositions(joint, new_values.data()); update = true; } } From 70537f037a87fbfa8bb51586cac247fd59a58e53 Mon Sep 17 00:00:00 2001 From: Daniel Wang Date: Wed, 14 Aug 2019 18:46:27 -0700 Subject: [PATCH 31/96] fix the invalid iterator issue (#1623) Signed-off-by: Daniel Wang --- moveit_setup_assistant/src/tools/moveit_config_data.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_setup_assistant/src/tools/moveit_config_data.cpp b/moveit_setup_assistant/src/tools/moveit_config_data.cpp index 77b4704390..0bbd81f4c2 100644 --- a/moveit_setup_assistant/src/tools/moveit_config_data.cpp +++ b/moveit_setup_assistant/src/tools/moveit_config_data.cpp @@ -775,7 +775,7 @@ void MoveItConfigData::outputFollowJointTrajectoryYAML(YAML::Emitter& emitter, emitter << YAML::EndMap; } } - ros_controllers_config_output.erase(controller_it); + controller_it = ros_controllers_config_output.erase(controller_it); emitter << YAML::EndMap; } else From 4acd3a75e4f5fdf3fdd1ac147648529758968c36 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Wed, 7 Aug 2019 14:01:55 -0600 Subject: [PATCH 32/96] Support benchmarking of full planning pipelines (#1531) ... instead of planning plugins only --- moveit_ros/benchmarks/README.md | 2 +- moveit_ros/benchmarks/examples/demo1.yaml | 4 +- moveit_ros/benchmarks/examples/demo2.yaml | 6 +- .../benchmarks/examples/demo_fanuc.launch | 2 +- .../benchmarks/examples/demo_obstacles.yaml | 8 +- .../benchmarks/examples/demo_panda.launch | 2 +- .../examples/demo_panda_all_planners.launch | 6 +- .../examples/demo_panda_all_planners.yaml | 8 +- .../demo_panda_all_planners_obstacles.launch | 6 +- .../moveit/benchmarks/BenchmarkExecutor.h | 5 +- .../moveit/benchmarks/BenchmarkOptions.h | 6 +- .../benchmarks/src/BenchmarkExecutor.cpp | 189 +++++++++--------- .../benchmarks/src/BenchmarkOptions.cpp | 44 ++-- moveit_ros/benchmarks/src/RunBenchmark.cpp | 6 +- 14 files changed, 148 insertions(+), 146 deletions(-) diff --git a/moveit_ros/benchmarks/README.md b/moveit_ros/benchmarks/README.md index ada7c8a485..4823b68253 100644 --- a/moveit_ros/benchmarks/README.md +++ b/moveit_ros/benchmarks/README.md @@ -2,4 +2,4 @@ This package provides methods to benchmark motion planning algorithms and aggregate/plot statistics. Results can be viewed in [Planner Arena](http://plannerarena.org/). -For more information and usage example please see [moveit tutorials](http://docs.ros.org/indigo/api/moveit_tutorials/html/doc/benchmarking_tutorial.html). +For more information and usage example please see [moveit tutorials](https://ros-planning.github.io/moveit_tutorials/doc/benchmarking/benchmarking_tutorial.html). diff --git a/moveit_ros/benchmarks/examples/demo1.yaml b/moveit_ros/benchmarks/examples/demo1.yaml index b930a8187a..7d6e9882a2 100644 --- a/moveit_ros/benchmarks/examples/demo1.yaml +++ b/moveit_ros/benchmarks/examples/demo1.yaml @@ -18,8 +18,8 @@ benchmark_config: output_directory: /tmp/moveit_benchmarks/ queries: Pick1 start_states: Start1 - planners: - - plugin: ompl_interface/OMPLPlanner + planning_pipelines: + - name: ompl planners: - RRTConnectkConfigDefault - BKPIECEkConfigDefault diff --git a/moveit_ros/benchmarks/examples/demo2.yaml b/moveit_ros/benchmarks/examples/demo2.yaml index ba6048b01a..cb25a6c6c6 100644 --- a/moveit_ros/benchmarks/examples/demo2.yaml +++ b/moveit_ros/benchmarks/examples/demo2.yaml @@ -18,12 +18,12 @@ benchmark_config: output_directory: /home/benchmarks/ queries: .* start_states: .* - planners: - - plugin: ompl_interface/OMPLPlanner + planning_pipelines: + - name: ompl planners: - RRTConnectkConfigDefault - BKPIECEkConfigDefault - KPIECEkConfigDefault - - plugin: my_plugin_ns/my_plugin + - name: my_pipeline planners: - MyPlanner diff --git a/moveit_ros/benchmarks/examples/demo_fanuc.launch b/moveit_ros/benchmarks/examples/demo_fanuc.launch index 75b4f91b8d..cfecc6f5c5 100644 --- a/moveit_ros/benchmarks/examples/demo_fanuc.launch +++ b/moveit_ros/benchmarks/examples/demo_fanuc.launch @@ -8,7 +8,7 @@ - + diff --git a/moveit_ros/benchmarks/examples/demo_obstacles.yaml b/moveit_ros/benchmarks/examples/demo_obstacles.yaml index 8616b78596..d6a3c3b504 100644 --- a/moveit_ros/benchmarks/examples/demo_obstacles.yaml +++ b/moveit_ros/benchmarks/examples/demo_obstacles.yaml @@ -18,16 +18,16 @@ benchmark_config: output_directory: /tmp/moveit_benchmarks/ queries: .* start_states: .* - planners: - - plugin: ompl_interface/OMPLPlanner + planning_pipelines: + - name: ompl planners: - RRTConnectkConfigDefault - BKPIECEkConfigDefault - KPIECEkConfigDefault - - plugin: chomp_interface/CHOMPPlanner + - name: chomp planners: - CHOMP - - plugin: stomp_moveit/StompPlannerManager + - name: stomp planners: - STOMP diff --git a/moveit_ros/benchmarks/examples/demo_panda.launch b/moveit_ros/benchmarks/examples/demo_panda.launch index f82b5ef8c8..66742658e5 100644 --- a/moveit_ros/benchmarks/examples/demo_panda.launch +++ b/moveit_ros/benchmarks/examples/demo_panda.launch @@ -8,7 +8,7 @@ - + diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch b/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch index 161cd4478b..f0d60f6105 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch @@ -8,15 +8,15 @@ - + - + - + diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml index aaa20a017d..3fc13adebc 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml @@ -18,16 +18,16 @@ benchmark_config: output_directory: /tmp/moveit_benchmarks/ queries: .* start_states: .* - planners: - - plugin: ompl_interface/OMPLPlanner + planning_pipelines: + - name: ompl planners: - RRTConnectkConfigDefault - BKPIECEkConfigDefault - KPIECEkConfigDefault - - plugin: chomp_interface/CHOMPPlanner + - name: chomp planners: - CHOMP - - plugin: stomp_moveit/StompPlannerManager + - name: stomp planners: - STOMP diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch b/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch index 205bab2081..25b0a50715 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch @@ -8,15 +8,15 @@ - + - + - + diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h index 9dfc5b8023..92a0a82a36 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkExecutor.h @@ -45,7 +45,7 @@ #include #include #include -#include +#include #include #include @@ -212,8 +212,7 @@ class BenchmarkExecutor BenchmarkOptions options_; - std::shared_ptr> planner_plugin_loader_; - std::map planner_interfaces_; + std::map planning_pipelines_; std::vector benchmark_data_; diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index dbd46c4cdb..0006d42f39 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -68,8 +68,8 @@ class BenchmarkOptions const std::string& getPathConstraintRegex() const; const std::string& getTrajectoryConstraintRegex() const; void getGoalOffsets(std::vector& offsets) const; - const std::map>& getPlannerConfigurations() const; - void getPlannerPluginList(std::vector& plugin_list) const; + const std::map>& getPlanningPipelineConfigurations() const; + void getPlanningPipelineNames(std::vector& planning_pipeline_names) const; const std::string& getWorkspaceFrameID() const; const moveit_msgs::WorkspaceParameters& getWorkspaceParameters() const; @@ -103,7 +103,7 @@ class BenchmarkOptions double goal_offsets[6]; /// planner configurations - std::map> planners_; + std::map> planning_pipelines_; moveit_msgs::WorkspaceParameters workspace_; }; diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index b48dd98a95..4f717cd97a 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -71,17 +71,6 @@ BenchmarkExecutor::BenchmarkExecutor(const std::string& robot_description_param) tcs_ = nullptr; psm_ = new planning_scene_monitor::PlanningSceneMonitor(robot_description_param); planning_scene_ = psm_->getPlanningScene(); - - // Initialize the class loader for planner plugins - try - { - planner_plugin_loader_.reset(new pluginlib::ClassLoader( - "moveit_core", "planning_interface::PlannerManager")); - } - catch (pluginlib::PluginlibException& ex) - { - ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); - } } BenchmarkExecutor::~BenchmarkExecutor() @@ -94,46 +83,39 @@ BenchmarkExecutor::~BenchmarkExecutor() delete psm_; } -void BenchmarkExecutor::initialize(const std::vector& plugin_classes) +void BenchmarkExecutor::initialize(const std::vector& planning_pipeline_names) { - planner_interfaces_.clear(); + planning_pipelines_.clear(); - // Load the planning plugins - const std::vector& classes = planner_plugin_loader_->getDeclaredClasses(); - - for (const std::string& planner_plugin_name : plugin_classes) + ros::NodeHandle pnh("~"); + for (const std::string& planning_pipeline_name : planning_pipeline_names) { - std::vector::const_iterator it = std::find(classes.begin(), classes.end(), planner_plugin_name); - if (it == classes.end()) - { - ROS_ERROR("Failed to find plugin_class %s", planner_plugin_name.c_str()); - return; - } - - try - { - planning_interface::PlannerManagerPtr p = planner_plugin_loader_->createUniqueInstance(planner_plugin_name); - p->initialize(planning_scene_->getRobotModel(), ""); + // Initialize planning pipelines from configured child namespaces + ros::NodeHandle child_nh(pnh, planning_pipeline_name); + planning_pipeline::PlanningPipelinePtr pipeline(new planning_pipeline::PlanningPipeline( + planning_scene_->getRobotModel(), child_nh, "planning_plugin", "request_adapters")); - p->getPlannerConfigurations(); - planner_interfaces_[planner_plugin_name] = p; - } - catch (pluginlib::PluginlibException& ex) + // Verify the pipeline has successfully initialized a planner + if (!pipeline->getPlannerManager()) { - ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what()); + ROS_ERROR("Failed to initialize planning pipeline '%s'", planning_pipeline_name.c_str()); + continue; } + + // Disable visualizations and store pipeline + pipeline->displayComputedMotionPlans(false); + pipeline->checkSolutionPaths(false); + planning_pipelines_[planning_pipeline_name] = pipeline; } - // error check - if (planner_interfaces_.empty()) - ROS_ERROR("No planning plugins have been loaded. Nothing to do for the benchmarking service."); + // Error check + if (planning_pipelines_.empty()) + ROS_ERROR("No planning pipelines have been loaded. Nothing to do for the benchmarking service."); else { - std::stringstream ss; - for (std::map::const_iterator it = planner_interfaces_.begin(); - it != planner_interfaces_.end(); ++it) - ss << it->first << " "; - ROS_INFO("Available planner instances: %s", ss.str().c_str()); + ROS_INFO("Available planning pipelines:"); + for (const std::pair& entry : planning_pipelines_) + ROS_INFO_STREAM("Pipeline: " << entry.first << ", Planner: " << entry.second->getPlannerPluginName()); } } @@ -206,9 +188,9 @@ void BenchmarkExecutor::addQueryCompletionEvent(const QueryCompletionEventFuncti bool BenchmarkExecutor::runBenchmarks(const BenchmarkOptions& opts) { - if (planner_interfaces_.empty()) + if (planning_pipelines_.empty()) { - ROS_ERROR("No planning interfaces configured. Did you call BenchmarkExecutor::initialize?"); + ROS_ERROR("No planning pipelines configured. Did you call BenchmarkExecutor::initialize?"); return false; } @@ -217,7 +199,7 @@ bool BenchmarkExecutor::runBenchmarks(const BenchmarkOptions& opts) if (initializeBenchmarks(opts, scene_msg, queries)) { - if (!queriesAndPlannersCompatible(queries, opts.getPlannerConfigurations())) + if (!queriesAndPlannersCompatible(queries, opts.getPlanningPipelineConfigurations())) return false; for (std::size_t i = 0; i < queries.size(); ++i) @@ -241,7 +223,7 @@ bool BenchmarkExecutor::runBenchmarks(const BenchmarkOptions& opts) ROS_INFO("Benchmarking query '%s' (%lu of %lu)", queries[i].name.c_str(), i + 1, queries.size()); ros::WallTime start_time = ros::WallTime::now(); - runBenchmark(queries[i].request, options_.getPlannerConfigurations(), options_.getNumRuns()); + runBenchmark(queries[i].request, options_.getPlanningPipelineConfigurations(), options_.getNumRuns()); double duration = (ros::WallTime::now() - start_time).toSec(); for (QueryCompletionEventFunction& query_end_fn : query_end_fns_) @@ -259,14 +241,15 @@ bool BenchmarkExecutor::queriesAndPlannersCompatible(const std::vector>& planners) { // Make sure that the planner interfaces can service the desired queries - for (std::map::const_iterator it = planner_interfaces_.begin(); - it != planner_interfaces_.end(); ++it) + for (const std::pair& pipeline_entry : planning_pipelines_) { for (const BenchmarkRequest& request : requests) { - if (!it->second->canServiceRequest(request.request)) + if (!pipeline_entry.second->getPlannerManager()->canServiceRequest(request.request)) { - ROS_ERROR("Interface '%s' cannot service the benchmark request '%s'", it->first.c_str(), request.name.c_str()); + ROS_ERROR("Interface '%s' in pipeline '%s' cannot service the benchmark request '%s'", + pipeline_entry.second->getPlannerPluginName().c_str(), pipeline_entry.first.c_str(), + request.name.c_str()); return false; } } @@ -278,7 +261,7 @@ bool BenchmarkExecutor::queriesAndPlannersCompatible(const std::vector& requests) { - if (!plannerConfigurationsExist(opts.getPlannerConfigurations(), opts.getGroupName())) + if (!plannerConfigurationsExist(opts.getPlanningPipelineConfigurations(), opts.getGroupName())) return false; std::vector start_states; @@ -484,6 +467,10 @@ void BenchmarkExecutor::createRequestCombinations(const BenchmarkRequest& breque { for (const StartState& start_state : start_states) { + // Skip start states that have the same name as the goal + if (start_state.name == brequest.name) + continue; + BenchmarkRequest new_brequest = brequest; new_brequest.request.start_state = start_state.state; @@ -504,33 +491,29 @@ void BenchmarkExecutor::createRequestCombinations(const BenchmarkRequest& breque } } -bool BenchmarkExecutor::plannerConfigurationsExist(const std::map>& planners, - const std::string& group_name) +bool BenchmarkExecutor::plannerConfigurationsExist( + const std::map>& pipeline_configurations, const std::string& group_name) { // Make sure planner plugins exist - for (std::map>::const_iterator it = planners.begin(); it != planners.end(); - ++it) + for (const std::pair>& pipeline_config_entry : pipeline_configurations) { - bool plugin_exists = false; - for (std::map::const_iterator planner_it = - planner_interfaces_.begin(); - planner_it != planner_interfaces_.end() && !plugin_exists; ++planner_it) + bool pipeline_exists = false; + for (const std::pair& pipeline_entry : planning_pipelines_) { - plugin_exists = planner_it->first == it->first; + pipeline_exists = pipeline_entry.first == pipeline_config_entry.first; } - if (!plugin_exists) + if (!pipeline_exists) { - ROS_ERROR("Planning plugin '%s' does NOT exist", it->first.c_str()); + ROS_ERROR("Planning pipeline '%s' does NOT exist", pipeline_config_entry.first.c_str()); return false; } } - // Make sure planning algorithms exist within those plugins - for (std::map>::const_iterator it = planners.begin(); it != planners.end(); - ++it) + // Make sure planners exist within those pipelines + for (const std::pair>& entry : pipeline_configurations) { - planning_interface::PlannerManagerPtr pm = planner_interfaces_[it->first]; + planning_interface::PlannerManagerPtr pm = planning_pipelines_[entry.first]->getPlannerManager(); const planning_interface::PlannerConfigurationMap& config_map = pm->getPlannerConfigurations(); // if the planner is chomp or stomp skip this function and return true for checking planner configurations for the @@ -539,24 +522,22 @@ bool BenchmarkExecutor::plannerConfigurationsExist(const std::mapgetDescription().compare("stomp") || pm->getDescription().compare("chomp")) continue; - for (std::size_t i = 0; i < it->second.size(); ++i) + for (std::size_t i = 0; i < entry.second.size(); ++i) { bool planner_exists = false; - for (planning_interface::PlannerConfigurationMap::const_iterator map_it = config_map.begin(); - map_it != config_map.end() && !planner_exists; ++map_it) + for (const std::pair& config_entry : config_map) { - std::string planner_name = group_name + "[" + it->second[i] + "]"; - planner_exists = (map_it->second.group == group_name && map_it->second.name == planner_name); + std::string planner_name = group_name + "[" + entry.second[i] + "]"; + planner_exists = (config_entry.second.group == group_name && config_entry.second.name == planner_name); } if (!planner_exists) { - ROS_ERROR("Planner '%s' does NOT exist for group '%s' in pipeline '%s'", it->second[i].c_str(), - group_name.c_str(), it->first.c_str()); + ROS_ERROR("Planner '%s' does NOT exist for group '%s' in pipeline '%s'", entry.second[i].c_str(), + group_name.c_str(), entry.first.c_str()); std::cout << "There are " << config_map.size() << " planner entries: " << std::endl; - for (planning_interface::PlannerConfigurationMap::const_iterator map_it = config_map.begin(); - map_it != config_map.end() && !planner_exists; ++map_it) - std::cout << map_it->second.name << std::endl; + for (const auto& config_map_entry : config_map) + std::cout << config_map_entry.second.name << std::endl; return false; } } @@ -756,21 +737,24 @@ bool BenchmarkExecutor::loadTrajectoryConstraints(const std::string& regex, } void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, - const std::map>& planners, int runs) + const std::map>& pipeline_map, int runs) { benchmark_data_.clear(); unsigned int num_planners = 0; - for (const std::pair>& planner : planners) - num_planners += planner.second.size(); + for (const std::pair>& pipeline_entry : pipeline_map) + num_planners += pipeline_entry.second.size(); boost::progress_display progress(num_planners * runs, std::cout); - // Iterate through all planner plugins - for (const std::pair>& planner : planners) + // Iterate through all planning pipelines + for (const std::pair>& pipeline_entry : pipeline_map) { - // Iterate through all planners associated with the plugin - for (std::size_t i = 0; i < planner.second.size(); ++i) + planning_pipeline::PlanningPipelinePtr planning_pipeline = planning_pipelines_[pipeline_entry.first]; + // Use the planning context if the pipeline only contains the planner plugin + bool use_planning_context = planning_pipeline->getAdapterPluginNames().empty(); + // Iterate through all planners configured for the pipeline + for (const std::string& planner_id : pipeline_entry.second) { // This container stores all of the benchmark data for this planner PlannerBenchmarkData planner_data(runs); @@ -778,14 +762,17 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, std::vector responses(runs); std::vector solved(runs); - request.planner_id = planner.second[i]; + request.planner_id = planner_id; // Planner start events for (PlannerStartEventFunction& planner_start_fn : planner_start_fns_) planner_start_fn(request, planner_data); - planning_interface::PlanningContextPtr context = - planner_interfaces_[planner.first]->getPlanningContext(planning_scene_, request); + planning_interface::PlanningContextPtr planning_context; + if (use_planning_context) + planning_context = planning_pipeline->getPlannerManager()->getPlanningContext(planning_scene_, request); + + // Iterate runs for (int j = 0; j < runs; ++j) { // Pre-run events @@ -794,7 +781,23 @@ void BenchmarkExecutor::runBenchmark(moveit_msgs::MotionPlanRequest request, // Solve problem ros::WallTime start = ros::WallTime::now(); - solved[j] = context->solve(responses[j]); + if (use_planning_context) + { + solved[j] = planning_context->solve(responses[j]); + } + else + { + // The planning pipeline does not support MotionPlanDetailedResponse + planning_interface::MotionPlanResponse response; + solved[j] = planning_pipeline->generatePlan(planning_scene_, request, response); + responses[j].error_code_ = response.error_code_; + if (response.trajectory_) + { + responses[j].description_.push_back("plan"); + responses[j].trajectory_.push_back(response.trajectory_); + responses[j].processing_time_.push_back(response.planning_time_); + } + } double total_time = (ros::WallTime::now() - start).toSec(); // Collect data @@ -1037,11 +1040,11 @@ bool BenchmarkExecutor::computeTrajectoryDistance(const robot_trajectory::RobotT void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std::string& start_time, double benchmark_duration) { - const std::map>& planners = options_.getPlannerConfigurations(); + const std::map>& pipelines = options_.getPlanningPipelineConfigurations(); size_t num_planners = 0; - for (const std::pair>& planner : planners) - num_planners += planner.second.size(); + for (const std::pair>& pipeline : pipelines) + num_planners += pipeline.second.size(); std::string hostname = getHostname(); if (hostname.empty()) @@ -1091,12 +1094,12 @@ void BenchmarkExecutor::writeOutput(const BenchmarkRequest& brequest, const std: out << num_planners << " planners" << std::endl; size_t run_id = 0; - for (const std::pair>& planner : planners) + for (const std::pair>& pipeline : pipelines) { - for (std::size_t i = 0; i < planner.second.size(); ++i, ++run_id) + for (std::size_t i = 0; i < pipeline.second.size(); ++i, ++run_id) { - // Write the name of the planner. - out << planner.second[i] << std::endl; + // Write the name of the planner and the used pipeline + out << pipeline.second[i] << " (" << pipeline.first << ")" << std::endl; // in general, we could have properties specific for a planner; // right now, we do not include such properties diff --git a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp index 134d1d4017..1ed9c512a1 100644 --- a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp @@ -142,16 +142,16 @@ void BenchmarkOptions::getGoalOffsets(std::vector& offsets) const memcpy(&offsets[0], goal_offsets, 6 * sizeof(double)); } -const std::map>& BenchmarkOptions::getPlannerConfigurations() const +const std::map>& BenchmarkOptions::getPlanningPipelineConfigurations() const { - return planners_; + return planning_pipelines_; } -void BenchmarkOptions::getPlannerPluginList(std::vector& plugin_list) const +void BenchmarkOptions::getPlanningPipelineNames(std::vector& planning_pipeline_names) const { - plugin_list.clear(); - for (const std::pair>& planner : planners_) - plugin_list.push_back(planner.first); + planning_pipeline_names.clear(); + for (const std::pair>& planning_pipeline : planning_pipelines_) + planning_pipeline_names.push_back(planning_pipeline.first); } const std::string& BenchmarkOptions::getWorkspaceFrameID() const @@ -237,48 +237,48 @@ void BenchmarkOptions::readWorkspaceParameters(ros::NodeHandle& nh) void BenchmarkOptions::readPlannerConfigs(ros::NodeHandle& nh) { - planners_.clear(); + planning_pipelines_.clear(); - XmlRpc::XmlRpcValue planner_configs; - if (nh.getParam("benchmark_config/planners", planner_configs)) + XmlRpc::XmlRpcValue pipeline_configs; + if (nh.getParam("benchmark_config/planning_pipelines", pipeline_configs)) { - if (planner_configs.getType() != XmlRpc::XmlRpcValue::TypeArray) + if (pipeline_configs.getType() != XmlRpc::XmlRpcValue::TypeArray) { - ROS_ERROR("Expected a list of planner configurations to benchmark"); + ROS_ERROR("Expected a list of planning pipeline configurations to benchmark"); return; } - for (int i = 0; i < planner_configs.size(); ++i) // NOLINT(modernize-loop-convert) + for (int i = 0; i < pipeline_configs.size(); ++i) // NOLINT(modernize-loop-convert) { - if (planner_configs[i].getType() != XmlRpc::XmlRpcValue::TypeStruct) + if (pipeline_configs[i].getType() != XmlRpc::XmlRpcValue::TypeStruct) { - ROS_WARN("Improper YAML type for planner configurations"); + ROS_WARN("Improper YAML type for planning pipeline configurations"); continue; } - if (!planner_configs[i].hasMember("plugin") || !planner_configs[i].hasMember("planners")) + if (!pipeline_configs[i].hasMember("name") || !pipeline_configs[i].hasMember("planners")) { ROS_WARN("Malformed YAML for planner configurations"); continue; } - if (planner_configs[i]["planners"].getType() != XmlRpc::XmlRpcValue::TypeArray) + if (pipeline_configs[i]["planners"].getType() != XmlRpc::XmlRpcValue::TypeArray) { ROS_WARN("Expected a list of planners to benchmark"); continue; } - const std::string plugin = planner_configs[i]["plugin"]; - ROS_INFO("Reading in planner names for plugin '%s'", plugin.c_str()); + const std::string pipeline_name = pipeline_configs[i]["name"]; + ROS_INFO("Reading in planner names for planning pipeline '%s'", pipeline_name.c_str()); std::vector planners; - planners.reserve(planner_configs[i]["planners"].size()); - for (int j = 0; j < planner_configs[i]["planners"].size(); ++j) - planners.emplace_back(planner_configs[i]["planners"][j]); + planners.reserve(pipeline_configs[i]["planners"].size()); + for (int j = 0; j < pipeline_configs[i]["planners"].size(); ++j) + planners.emplace_back(pipeline_configs[i]["planners"][j]); for (std::size_t j = 0; j < planners.size(); ++j) ROS_INFO(" [%lu]: %s", j, planners[j].c_str()); - planners_[plugin] = planners; + planning_pipelines_[pipeline_name] = planners; } } } diff --git a/moveit_ros/benchmarks/src/RunBenchmark.cpp b/moveit_ros/benchmarks/src/RunBenchmark.cpp index 14082cbcdc..19496e54e6 100644 --- a/moveit_ros/benchmarks/src/RunBenchmark.cpp +++ b/moveit_ros/benchmarks/src/RunBenchmark.cpp @@ -51,9 +51,9 @@ int main(int argc, char** argv) // Setup benchmark server moveit_ros_benchmarks::BenchmarkExecutor server; - std::vector plugins; - opts.getPlannerPluginList(plugins); - server.initialize(plugins); + std::vector planning_pipelines; + opts.getPlanningPipelineNames(planning_pipelines); + server.initialize(planning_pipelines); // Running benchmarks if (!server.runBenchmarks(opts)) From af106bed1f1188ce85b4c7b6558c9d26ea773a65 Mon Sep 17 00:00:00 2001 From: Jafar Abdi Date: Thu, 15 Aug 2019 16:53:09 +0300 Subject: [PATCH 33/96] newRobotStateCallback(): use new .hide member of DisplayRobotState msg to visually hide the robot --- .../robot_state_rviz_plugin/src/robot_state_display.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index 0865765a83..d843923605 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -314,6 +314,9 @@ void RobotStateDisplay::newRobotStateCallback(const moveit_msgs::DisplayRobotSta setStatus(rviz::StatusProperty::Error, "RobotState", e.what()); return; } + + robot_->setVisible(!state_msg->hide); + update_state_ = true; } From f6a24033bf784d4a299bd185a92480fa6bb592ef Mon Sep 17 00:00:00 2001 From: Omid Heidari Date: Thu, 15 Aug 2019 16:17:10 -0600 Subject: [PATCH 34/96] MVP TrajOpt Planner Plugin (#1593) * added solve from tesseract. added launch file improved test_trajopt node edited package.xml * TrajOpt Planner (Empty Template) (#1478) * Created EmptyPlan, a MoveIt planning plugin template * added trajopt from example_planner * fixed trajopt_planner_mannager * modified emaptyplan_planner_manager.cpp * applied Dave's modifications * The rest of the modifications from Dave's comments * removed moveit_ros_planning dependency from package.xml * fixed clangformat error and dependency issu * added include directory * edited package.xml * added include * remove include * remove version_gte from package.xml * updated the setup assitant to work with trajopt planner * removed unsuded part in initialize() from trajopt_planner_manager.cpp, kept the initialize() itself for later use * Update moveit_planners/trajopt/src/trajopt_planner_manager.cpp Co-Authored-By: Dave Coleman * added README added description to trajopt_interface_plugin_description.xml * updated resp req updated planning context working trajopt without any velocity constraint * added trajopt_interface class * changed the architectrue and used TrajoptInterface class to contain the solve function details. Created a TrajOptInterface object in TrajoptPlanningContext class instead * added kinematic_terms in problem_description, added comments anout term_type added ProblemInfo, TermInfo, InitInfo, BasicInfo in kinematic_terms, added operator() added ConstructProblem added some param for problem_info * moved rotVec and concat from kinematics_term header to implementation in problem_Description, added term_type used MotionPlaneRequest from planning_interface instead that of moveit_msgs for solve function input added generateInitiaTrajectory added basic_info to problem_info * added panda_omple_planning added checkParameterSize function in problem_description added JointPoseTermInfo::hatch in problem_description added res.error.code.val to check the request in trajopt_interface.cpp convert req.goal_constraint to JointPoseTermInfo in trajopt_interface.cpp feed the response with the trajopt solution in trajopt_interface.cpp remove comments from trajopt_planning_context.cpp * addressed the comments fixed start state corrected the yaml file multiple joint constraints * addressed some comments leave setup assistant changes for later on another PR cleaned up test_trajopt added unittest * added kinematic DOF of the active joint model group to TrajOptProblem class added name_ for ROS_DEBUG_STREAM_NAMED addressed the comments moved launch file to moveit_tutorial moved yaml file to panda_moveit_config used bullet for collision checking * handled reading the request from MotionPlanning Display in RViz * Added comments about initial trajectory changed my email address renamed rotVec and concat added tesseract license * clang format * applied Henning's comments * added catkin ignore to ignore this package for now as it has dependencies. The next PR wont have any dependencies * clang format * addressed the comments * renamed hatch to addObjectiveTerms * added a unittest for goal tolerance * addressed Dave's comments * added catkin_ignore * addressed Bryce's comments --- .gitignore | 6 +- moveit_planners/trajopt/CATKIN_IGNORE | 0 moveit_planners/trajopt/CMakeLists.txt | 113 ++++ moveit_planners/trajopt/README.md | 1 + .../trajopt_interface/kinematic_terms.h | 93 +++ .../trajopt_interface/problem_description.h | 367 +++++++++++ .../trajopt_interface/trajopt_interface.h | 77 +++ .../trajopt_planning_context.h | 32 + moveit_planners/trajopt/package.xml | 32 + .../trajopt/src/kinematic_terms.cpp | 64 ++ .../trajopt/src/problem_description.cpp | 599 ++++++++++++++++++ .../trajopt/src/trajopt_interface.cpp | 463 ++++++++++++++ .../trajopt/src/trajopt_planner_manager.cpp | 141 +++++ .../trajopt/src/trajopt_planning_context.cpp | 76 +++ .../trajopt/test/trajectory_test.cpp | 212 +++++++ .../trajopt/test/trajectory_test.test | 10 + .../trajopt_interface_plugin_description.xml | 7 + .../launch/run_benchmark_trajopt.launch | 22 + .../trajopt_planning_pipeline.launch.xml | 22 + 19 files changed, 2334 insertions(+), 3 deletions(-) create mode 100644 moveit_planners/trajopt/CATKIN_IGNORE create mode 100644 moveit_planners/trajopt/CMakeLists.txt create mode 100644 moveit_planners/trajopt/README.md create mode 100644 moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h create mode 100644 moveit_planners/trajopt/include/trajopt_interface/problem_description.h create mode 100644 moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h create mode 100644 moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h create mode 100644 moveit_planners/trajopt/package.xml create mode 100644 moveit_planners/trajopt/src/kinematic_terms.cpp create mode 100644 moveit_planners/trajopt/src/problem_description.cpp create mode 100644 moveit_planners/trajopt/src/trajopt_interface.cpp create mode 100644 moveit_planners/trajopt/src/trajopt_planner_manager.cpp create mode 100644 moveit_planners/trajopt/src/trajopt_planning_context.cpp create mode 100644 moveit_planners/trajopt/test/trajectory_test.cpp create mode 100644 moveit_planners/trajopt/test/trajectory_test.test create mode 100644 moveit_planners/trajopt/trajopt_interface_plugin_description.xml create mode 100644 moveit_setup_assistant/templates/moveit_config_pkg_template/launch/run_benchmark_trajopt.launch create mode 100644 moveit_setup_assistant/templates/moveit_config_pkg_template/launch/trajopt_planning_pipeline.launch.xml diff --git a/.gitignore b/.gitignore index 9877f9248d..808fe85341 100644 --- a/.gitignore +++ b/.gitignore @@ -51,10 +51,10 @@ qtcreator-* # Vim *.swp -# Catkin custom files -CATKIN_IGNORE - # Continous Integration .moveit_ci *.pyc + +#gdb +*.gdb diff --git a/moveit_planners/trajopt/CATKIN_IGNORE b/moveit_planners/trajopt/CATKIN_IGNORE new file mode 100644 index 0000000000..e69de29bb2 diff --git a/moveit_planners/trajopt/CMakeLists.txt b/moveit_planners/trajopt/CMakeLists.txt new file mode 100644 index 0000000000..f93e000d34 --- /dev/null +++ b/moveit_planners/trajopt/CMakeLists.txt @@ -0,0 +1,113 @@ +cmake_minimum_required(VERSION 2.8.12) +project(moveit_planners_trajopt) + +add_compile_options(-std=c++14) + +if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) + set(CMAKE_BUILD_TYPE Release) +endif() + +find_package(catkin REQUIRED + COMPONENTS + moveit_core + moveit_visual_tools + moveit_ros_planning + moveit_ros_planning_interface + pluginlib + roscpp + rosparam_shortcuts + trajopt +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES + ${PROJECT_NAME} + INCLUDE_DIRS + CATKIN_DEPENDS + roscpp + pluginlib + moveit_core + moveit_visual_tools + moveit_ros_planning_interface + rosparam_shortcuts +) + +# The following include_directory should have include folder of the new planner. +include_directories( + include + ${catkin_INCLUDE_DIRS} + SYSTEM + ${Boost_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} +) + +add_library( + ${PROJECT_NAME} + src/trajopt_interface.cpp + src/problem_description.cpp + src/kinematic_terms.cpp + src/trajopt_planning_context.cpp +) + +target_link_libraries( + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${Boost_LIBRARIES} +) + +set_target_properties( + ${PROJECT_NAME} + PROPERTIES + VERSION + "${${PROJECT_NAME}_VERSION}" +) + +# TrajOpt planning plugin +add_library(moveit_trajopt_planner_plugin src/trajopt_planner_manager.cpp) +set_target_properties(moveit_trajopt_planner_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +target_link_libraries(moveit_trajopt_planner_plugin ${PROJECT_NAME} ${catkin_LIBRARIES}) + +############# +## Install ## +############# + +# Mark executables and/or libraries for installation +install( + TARGETS + moveit_trajopt_planner_plugin + ARCHIVE DESTINATION + ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION + ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION + ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +# Mark cpp header files for installation +install( + DIRECTORY + include/trajopt_interface/ + DESTINATION + ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +) + +install(FILES trajopt_interface_plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +############# +## Testing ## +############# + +if(CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + + add_rostest_gtest(trajectory_test test/trajectory_test.test test/trajectory_test.cpp) + target_link_libraries( + trajectory_test + ${LIBRARY_NAME} + ${catkin_LIBRARIES} + ${PROJECT_NAME} + ) + +endif() diff --git a/moveit_planners/trajopt/README.md b/moveit_planners/trajopt/README.md new file mode 100644 index 0000000000..98824eadb2 --- /dev/null +++ b/moveit_planners/trajopt/README.md @@ -0,0 +1 @@ +As of August 2019, this is a work in progress towards adding trajopt motion planning algorithm to MoveIt as a planner plugin. \ No newline at end of file diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h new file mode 100644 index 0000000000..96274cf9c7 --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -0,0 +1,93 @@ +#pragma once + +#include + +#include + +namespace trajopt_interface +{ +/** + * @brief Extracts the vector part of quaternion + */ +inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& matrix) +{ + Eigen::Quaterniond quaternion; + quaternion = matrix; + return Eigen::Vector3d(quaternion.x(), quaternion.y(), quaternion.z()); +} + +/** + * @brief Appends b to a of type VectorXd + */ +inline Eigen::VectorXd concatVector(const Eigen::VectorXd& vector_a, const Eigen::VectorXd& vector_b) +{ + Eigen::VectorXd out(vector_a.size() + vector_b.size()); + out.topRows(vector_a.size()) = vector_a; + out.middleRows(vector_a.size(), vector_b.size()) = vector_b; + return out; +} + +/** + * @brief Appends b to a of type T + */ +template +inline std::vector concatVector(const std::vector& vector_a, const std::vector& vector_b) +{ + std::vector out; + out.insert(out.end(), vector_a.begin(), vector_a.end()); + out.insert(out.end(), vector_b.begin(), vector_b.end()); + return out; +} + +/** + * @brief Used to calculate the error for StaticCartPoseTermInfo + * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc + */ +struct CartPoseErrCalculator : public sco::VectorOfVector +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Eigen::Isometry3d target_pose_inv_; + planning_scene::PlanningSceneConstPtr planning_scene_; + std::string link_; + Eigen::Isometry3d tcp_; + + CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, + const std::string& link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) + { + } + + Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override; +}; + +// TODO(omid): The following should be added and adjusted from trajopt +// JointPosEqCost +// JointPosIneqCost +// JointPosEqConstraint +// JointPosIneqConstraint + +struct JointVelErrCalculator : sco::VectorOfVector +{ + /** @brief Velocity target */ + double target_; + /** @brief Upper tolerance */ + double upper_tol_; + /** @brief Lower tolerance */ + double lower_tol_; + JointVelErrCalculator() : target_(0.0), upper_tol_(0.0), lower_tol_(0.0) + { + } + JointVelErrCalculator(double target, double upper_tol, double lower_tol) + : target_(target), upper_tol_(upper_tol), lower_tol_(lower_tol) + { + } + + Eigen::VectorXd operator()(const Eigen::VectorXd& var_vals) const; +}; + +struct JointVelJacobianCalculator : sco::MatrixOfVector +{ + Eigen::MatrixXd operator()(const Eigen::VectorXd& var_vals) const; +}; + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h new file mode 100644 index 0000000000..825c82262d --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -0,0 +1,367 @@ +#pragma once +#include +#include +#include + +#include +#include + +#include + +namespace trajopt_interface +{ +/** +@brief Used to apply cost/constraint to joint-space velocity + +Term is applied to every step between first_step and last_step. It applies two limits, upper_limits/lower_limits, +to the joint velocity subject to the following cases. + +* term_type = TT_COST +** upper_limit = lower_limit = 0 - Cost is applied with a SQUARED error scaled for each joint by coeffs +** upper_limit != lower_limit - 2 hinge costs are applied scaled for each joint by coeffs. If velocity < upper_limit and +velocity > lower_limit, no penalty. + +* term_type = TT_CNT +** upper_limit = lower_limit = 0 - Equality constraint is applied +** upper_limit != lower_limit - 2 Inequality constraints are applied. These are both satisfied when velocity < +upper_limit and velocity > lower_limit + +Note: coeffs, upper_limits, and lower_limits are optional. If a term is not given it will default to 0 for all joints. +If one value is given, this will be broadcast to all joints. + +Note: Velocity is calculated numerically using forward finite difference + +\f{align*}{ + cost = \sum_{t=0}^{T-2} \sum_j c_j (x_{t+1,j} - x_{t,j})^2 +\f} +where j indexes over DOF, and \f$c_j\f$ are the coeffs. +*/ + +struct TermInfo; +MOVEIT_CLASS_FORWARD(TermInfo); + +class TrajOptProblem; +MOVEIT_CLASS_FORWARD(TrajOptProblem); + +struct JointPoseTermInfo; +MOVEIT_CLASS_FORWARD(JointPoseTermInfo); + +struct CartPoseTermInfo; +MOVEIT_CLASS_FORWARD(CartPoseTermInfo); + +struct JointVelTermInfo; +MOVEIT_CLASS_FORWARD(JointVelTermInfo); + +struct ProblemInfo; +TrajOptProblemPtr ConstructProblem(const ProblemInfo&); + +enum TermType +{ + TT_COST = 0x1, // 0000 0001 + TT_CNT = 0x2, // 0000 0010 + TT_USE_TIME = 0x4, // 0000 0100 +}; + +struct BasicInfo +{ + /** @brief If true, first time step is fixed with a joint level constraint + If this is false, the starting point of the trajectory will + not be the current position of the robot. The use case example is: if we are trying to execute a process like + sanding the critical part which is the actual process path not how we get to the start of the process path. So we + plan the + process path first leaving the start free to hopefully get the most optimal and then we plan from the current + location with + start fixed to the start of the process path. It depends on what we want the default behavior to be + */ + bool start_fixed; + /** @brief Number of time steps (rows) in the optimization matrix */ + int n_steps; + sco::IntVec dofs_fixed; // optional + sco::ModelType convex_solver; // which convex solver to use + + /** @brief If true, the last column in the optimization matrix will be 1/dt */ + bool use_time = false; + /** @brief The upper limit of 1/dt values allowed in the optimization*/ + double dt_upper_lim = 1.0; + /** @brief The lower limit of 1/dt values allowed in the optimization*/ + double dt_lower_lim = 1.0; +}; + +/** +Initialization info read from json +*/ +struct InitInfo +{ + /** @brief Methods of initializing the optimization matrix. This defines how robot moves from the current + state to the start state + + STATIONARY: Initializes all joint values to the initial value (the current value in the env) + JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data + GIVEN_TRAJ: Initializes the matrix to a given trajectory + + In all cases the dt column (if present) is appended the selected method is defined. + */ + enum Type + { + STATIONARY, + JOINT_INTERPOLATED, + GIVEN_TRAJ, + }; + /** @brief Specifies the type of initialization to use */ + Type type; + /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used + to create initialization matrix. We need to give the goal information to this init info + */ + trajopt::TrajArray data; + // Eigen::VectorXd data_vec; + // trajopt::TrajArray data_trajectory; + /** @brief Default value the final column of the optimization is initialized too if time is being used */ + double dt = 1.0; +}; + +/** +When cost or constraint element of JSON doc is read, one of these guys gets +constructed to hold the parameters. +Then it later gets converted to a Cost object by the addObjectiveTerms method +*/ +struct TermInfo +{ + std::string name; + int term_type; + int getSupportedTypes() + { + return supported_term_types_; + } + // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; + virtual void addObjectiveTerms(TrajOptProblem& prob) = 0; + + static TermInfoPtr fromName(const std::string& type); + + /** + * Registers a user-defined TermInfo so you can use your own cost + * see function RegisterMakers.cpp + */ + using MakerFunc = TermInfoPtr (*)(void); + static void RegisterMaker(const std::string& type, MakerFunc); + + virtual ~TermInfo() = default; + +protected: + TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) + { + } + +private: + static std::map name_to_maker_; + int supported_term_types_; +}; + +struct ProblemInfo +{ +public: + BasicInfo basic_info; + sco::BasicTrustRegionSQPParameters opt_info; + std::vector cost_infos; + std::vector cnt_infos; + InitInfo init_info; + + planning_scene::PlanningSceneConstPtr planning_scene; + std::string planning_group_name; + + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) + : planning_scene(ps), planning_group_name(pg) + { + } +}; + +/** + * Holds all the data for a trajectory optimization problem + * so you can modify it programmatically, e.g. add your own costs + */ +class TrajOptProblem : public sco::OptProb +{ +public: + TrajOptProblem(); + TrajOptProblem(const ProblemInfo& problem_info); + virtual ~TrajOptProblem() = default; + /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ + sco::VarVector GetVarRow(int i, int start_col, int num_col) + { + return matrix_traj_vars.rblock(i, start_col, num_col); + } + /** @brief Returns the values of all joints for the specified timestep i.*/ + sco::VarVector GetVarRow(int i) + { + return matrix_traj_vars.row(i); + } + /** @brief Returns the value of the specified joint j for the specified timestep i.*/ + sco::Var& GetVar(int i, int j) + { + return matrix_traj_vars.at(i, j); + } + trajopt::VarArray& GetVars() + { + return matrix_traj_vars; + } + /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ + int GetNumSteps() + { + return matrix_traj_vars.rows(); + } + /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. + * Note that this is not necessarily the same as the kinematic DOF.*/ + int GetNumDOF() + { + return matrix_traj_vars.cols(); + } + /** @brief Returns the kinematic DOF of the active joint model group + */ + int GetActiveGroupNumDOF() + { + return dof_; + } + planning_scene::PlanningSceneConstPtr GetPlanningScene() + { + return planning_scene_; + } + void SetInitTraj(const trajopt::TrajArray& x) + { + matrix_init_traj = x; + } + trajopt::TrajArray GetInitTraj() + { + return matrix_init_traj; + } + // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); + /** @brief Returns TrajOptProb.has_time */ + bool GetHasTime() + { + return has_time; + } + /** @brief Sets TrajOptProb.has_time */ + void SetHasTime(bool tmp) + { + has_time = tmp; + } + +private: + /** @brief If true, the last column in the optimization matrix will be 1/dt */ + bool has_time; + /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ + trajopt::VarArray matrix_traj_vars; + planning_scene::PlanningSceneConstPtr planning_scene_; + std::string planning_group_; + /** @brief Kinematic DOF of the active joint model group */ + int dof_; + trajopt::TrajArray matrix_init_traj; +}; + +/** @brief This term is used when the goal frame is fixed in cartesian space + + Set term_type == TT_COST or TT_CNT for cost or constraint. +*/ +struct CartPoseTermInfo : public TermInfo +{ + // EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** @brief Timestep at which to apply term */ + int timestep; + /** @brief Cartesian position */ + Eigen::Vector3d xyz; + /** @brief Rotation quaternion */ + Eigen::Vector4d wxyz; + /** @brief coefficients for position and rotation */ + Eigen::Vector3d pos_coeffs, rot_coeffs; + /** @brief Link which should reach desired pose */ + std::string link; + /** @brief Static transform applied to the link */ + Eigen::Isometry3d tcp; + + CartPoseTermInfo(); + + /** @brief Used to add term to pci from json */ + // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void addObjectiveTerms(TrajOptProblem& prob) override; + + static TermInfoPtr create() + { + TermInfoPtr out(new CartPoseTermInfo()); + return out; + } +}; + +/** + \brief Joint space position cost + Position operates on a single point (unlike velocity, etc). This is b/c the primary usecase is joint-space + position waypoints + + \f{align*}{ + \sum_i c_i (x_i - xtarg_i)^2 + \f} + where \f$i\f$ indexes over dof and \f$c_i\f$ are coeffs + */ +struct JointPoseTermInfo : public TermInfo +{ + /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec coeffs; + /** @brief Vector of position targets. This is a required value. Size should be the DOF of the system */ + trajopt::DblVec targets; + /** @brief Vector of position upper limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec upper_tols; + /** @brief Vector of position lower limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec lower_tols; + /** @brief First time step to which the term is applied. Default: 0 */ + int first_step = 0; + /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ + int last_step = -1; + + /** @brief Initialize term with it's supported types */ + JointPoseTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) + { + } + + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void addObjectiveTerms(TrajOptProblem& prob) override; + + static TermInfoPtr create() + { + TermInfoPtr out(new JointPoseTermInfo()); + return out; + } +}; + +struct JointVelTermInfo : public TermInfo +{ + /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec coeffs; + /** @brief Vector of velocity targets. This is a required value. Size should be the DOF of the system */ + trajopt::DblVec targets; + /** @brief Vector of velocity upper limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec upper_tols; + /** @brief Vector of velocity lower limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec lower_tols; + /** @brief First time step to which the term is applied. Default: 0*/ + int first_step = 0; + /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ + int last_step = -1; + + /** @brief Initialize term with it's supported types */ + JointVelTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) + { + } + + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void addObjectiveTerms(TrajOptProblem& prob) override; + + static TermInfoPtr create() + { + TermInfoPtr out(new JointVelTermInfo()); + return out; + } +}; + +void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, + trajopt::TrajArray& init_traj); + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h new file mode 100644 index 0000000000..74432fa83c --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h @@ -0,0 +1,77 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, PickNik, LLC. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Omid Heidari */ +#pragma once + +#include +#include +#include +#include "problem_description.h" + +namespace trajopt_interface +{ +MOVEIT_CLASS_FORWARD(TrajOptInterface); + +class TrajOptInterface +{ +public: + TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); + + const sco::BasicTrustRegionSQPParameters& getParams() const + { + return params_; + } + + bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, + const planning_interface::MotionPlanRequest& req, moveit_msgs::MotionPlanDetailedResponse& res); + +protected: + /** @brief Configure everything using the param server */ + void setTrajOptParams(sco::BasicTrustRegionSQPParameters& param); + void setDefaultTrajOPtParams(); + void setProblemInfoParam(ProblemInfo& problem_info); + void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); + trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, + const std::vector& group_joint_names); + + ros::NodeHandle nh_; /// The ROS node handle + sco::BasicTrustRegionSQPParameters params_; + std::vector optimizer_callbacks_; + TrajOptProblemPtr trajopt_problem_; + std::string name_; +}; + +void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); +} diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h new file mode 100644 index 0000000000..12676f57e7 --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h @@ -0,0 +1,32 @@ +#pragma once + +#include + +#include +#include + +namespace trajopt_interface +{ +MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); + +class TrajOptPlanningContext : public planning_interface::PlanningContext +{ +public: + TrajOptPlanningContext(const std::string& name, const std::string& group, + const robot_model::RobotModelConstPtr& model); + ~TrajOptPlanningContext() override + { + } + + bool solve(planning_interface::MotionPlanResponse& res) override; + bool solve(planning_interface::MotionPlanDetailedResponse& res) override; + + bool terminate() override; + void clear() override; + +private: + moveit::core::RobotModelConstPtr robot_model_; + + TrajOptInterfacePtr trajopt_interface_; +}; +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/package.xml b/moveit_planners/trajopt/package.xml new file mode 100644 index 0000000000..050d71b5d4 --- /dev/null +++ b/moveit_planners/trajopt/package.xml @@ -0,0 +1,32 @@ + + moveit_planners_trajopt + 1.0.1 + TrajOpt planning plugin, an optimization based motion planner + + Omid Heidari + + Omid Heidari + MoveIt! Release Team + + BSD + + http://moveit.ros.org + https://github.com/ros-planning/moveit/issues + https://github.com/ros-planning/moveit + + catkin + + pluginlib + moveit_core + moveit_ros_planning + moveit_ros_planning_interface + moveit_visual_tools + roscpp + rosparam_shortcuts + trajopt + + + + + + diff --git a/moveit_planners/trajopt/src/kinematic_terms.cpp b/moveit_planners/trajopt/src/kinematic_terms.cpp new file mode 100644 index 0000000000..92d75fb78b --- /dev/null +++ b/moveit_planners/trajopt/src/kinematic_terms.cpp @@ -0,0 +1,64 @@ +#include +#include + +#include +#include + +#include "trajopt_interface/kinematic_terms.h" + +using namespace std; +using namespace sco; +using namespace Eigen; + +namespace trajopt_interface +{ +VectorXd CartPoseErrCalculator::operator()(const VectorXd& dof_vals) const +{ + // TODO: create the actual error function from information in planning scene + VectorXd err; + return err; +} + +VectorXd JointVelErrCalculator::operator()(const VectorXd& var_vals) const +{ + assert(var_vals.rows() % 2 == 0); + // var_vals = (theta_t1, theta_t2, theta_t3 ... 1/dt_1, 1/dt_2, 1/dt_3 ...) + int half = static_cast(var_vals.rows() / 2); + int num_vels = half - 1; + // (x1-x0)*(1/dt) + VectorXd vel = (var_vals.segment(1, num_vels) - var_vals.segment(0, num_vels)).array() * + var_vals.segment(half + 1, num_vels).array(); + + // Note that for equality terms tols are 0, so error is effectively doubled + VectorXd result(vel.rows() * 2); + result.topRows(vel.rows()) = -(upper_tol_ - (vel.array() - target_)); + result.bottomRows(vel.rows()) = lower_tol_ - (vel.array() - target_); + return result; +} + +MatrixXd JointVelJacobianCalculator::operator()(const VectorXd& var_vals) const +{ + // var_vals = (theta_t1, theta_t2, theta_t3 ... 1/dt_1, 1/dt_2, 1/dt_3 ...) + int num_vals = static_cast(var_vals.rows()); + int half = num_vals / 2; + int num_vels = half - 1; + MatrixXd jac = MatrixXd::Zero(num_vels * 2, num_vals); + + for (int i = 0; i < num_vels; i++) + { + // v = (j_i+1 - j_i)*(1/dt) + // We calculate v with the dt from the second pt + int time_index = i + half + 1; + jac(i, i) = -1.0 * var_vals(time_index); + jac(i, i + 1) = 1.0 * var_vals(time_index); + jac(i, time_index) = var_vals(i + 1) - var_vals(i); + // All others are 0 + } + + // bottom half is negative velocities + jac.bottomRows(num_vels) = -jac.topRows(num_vels); + + return jac; +} + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/src/problem_description.cpp b/moveit_planners/trajopt/src/problem_description.cpp new file mode 100644 index 0000000000..7cd678282c --- /dev/null +++ b/moveit_planners/trajopt/src/problem_description.cpp @@ -0,0 +1,599 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, John Schulman + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * http://opensource.org/licenses/BSD-2-Clause + *********************************************************************/ + +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "trajopt_interface/problem_description.h" +#include "trajopt_interface/kinematic_terms.h" + +/** + * @brief Checks the size of the parameter given and throws if incorrect + * @param parameter The vector whose size is getting checked + * @param expected_size The expected size of the vector + * @param name The name to use when printing an error or warning + * @param apply_first If true and only one value is given, broadcast value to length of expected_size + */ +void checkParameterSize(trajopt::DblVec& parameter, const unsigned int& expected_size, const std::string& name, + const bool& apply_first = true) +{ + if (apply_first == true && parameter.size() == 1) + { + parameter = trajopt::DblVec(expected_size, parameter[0]); + ROS_INFO("1 %s given. Applying to all %i joints", name.c_str(), expected_size); + } + else if (parameter.size() != expected_size) + { + PRINT_AND_THROW(boost::format("wrong number of %s. expected %i got %i") % name % expected_size % parameter.size()); + } +} + +namespace trajopt_interface +{ +TrajOptProblem::TrajOptProblem() +{ +} + +TrajOptProblem::TrajOptProblem(const ProblemInfo& problem_info) + : OptProb(problem_info.basic_info.convex_solver) + , planning_scene_(problem_info.planning_scene) + , planning_group_(problem_info.planning_group_name) +{ + robot_model::RobotModelConstPtr robot_model = planning_scene_->getRobotModel(); + robot_state::RobotState current_state = planning_scene_->getCurrentState(); + const robot_state::JointModelGroup* joint_model_group = current_state.getJointModelGroup(planning_group_); + + moveit::core::JointBoundsVector bounds = joint_model_group->getActiveJointModelsBounds(); + dof_ = joint_model_group->getActiveJointModelNames().size(); // or bounds.size(); + + int n_steps = problem_info.basic_info.n_steps; + + ROS_INFO(" ======================================= problem_description: limits"); + Eigen::MatrixX2d limits(dof_, 2); + for (int k = 0; k < limits.size() / 2; ++k) + { + moveit::core::JointModel::Bounds bound = *bounds[k]; + // In MoveIt, joints are considered to have multiple dofs but we only have single dof joints: + moveit::core::VariableBounds joint_bound = bound.front(); + + limits(k, 0) = joint_bound.min_position_; + limits(k, 1) = joint_bound.max_position_; + + ROS_INFO("joint %i with lower bound: %f, upper bound: %f", k, joint_bound.min_position_, joint_bound.max_position_); + } + + Eigen::VectorXd lower, upper; + lower = limits.col(0); + upper = limits.col(1); + + trajopt::DblVec vlower, vupper; + std::vector names; + for (int i = 0; i < n_steps; ++i) + { + for (int j = 0; j < dof_; ++j) + { + names.push_back((boost::format("j_%i_%i") % i % j).str()); + } + vlower.insert(vlower.end(), lower.data(), lower.data() + lower.size()); + vupper.insert(vupper.end(), upper.data(), upper.data() + upper.size()); + + if (problem_info.basic_info.use_time == true) + { + vlower.insert(vlower.end(), problem_info.basic_info.dt_lower_lim); + vupper.insert(vupper.end(), problem_info.basic_info.dt_upper_lim); + names.push_back((boost::format("dt_%i") % i).str()); + } + } + + sco::VarVector trajvarvec = createVariables(names, vlower, vupper); + matrix_traj_vars = trajopt::VarArray(n_steps, dof_ + (problem_info.basic_info.use_time ? 1 : 0), trajvarvec.data()); + // matrix_traj_vars is essentialy a matrix of elements like: + // j_0_0, j_0_1 ... + // j_1_0, j_1_1 ... + // its size is n_steps by n_dof +} + +TrajOptProblemPtr ConstructProblem(const ProblemInfo& pci) +{ + const BasicInfo& bi = pci.basic_info; + int n_steps = bi.n_steps; + + bool use_time = false; + // Check that all costs and constraints support the types that are specified in pci + for (TermInfoPtr cost : pci.cost_infos) + { + if (cost->term_type & TT_CNT) + ROS_WARN("%s is listed as a type TT_CNT but was added to cost_infos", (cost->name).c_str()); + if (!(cost->getSupportedTypes() & TT_COST)) + PRINT_AND_THROW(boost::format("%s is only a constraint, but you listed it as a cost") % cost->name); + if (cost->term_type & TT_USE_TIME) + { + use_time = true; + if (!(cost->getSupportedTypes() & TT_USE_TIME)) + PRINT_AND_THROW(boost::format("%s does not support time, but you listed it as a using time") % cost->name); + } + } + for (TermInfoPtr cnt : pci.cnt_infos) + { + if (cnt->term_type & TT_COST) + ROS_WARN("%s is listed as a type TT_COST but was added to cnt_infos", (cnt->name).c_str()); + if (!(cnt->getSupportedTypes() & TT_CNT)) + PRINT_AND_THROW(boost::format("%s is only a cost, but you listed it as a constraint") % cnt->name); + if (cnt->term_type & TT_USE_TIME) + { + use_time = true; + if (!(cnt->getSupportedTypes() & TT_USE_TIME)) + PRINT_AND_THROW(boost::format("%s does not support time, but you listed it as a using time") % cnt->name); + } + } + + // Check that if a cost or constraint uses time, basic_info is set accordingly + if ((use_time == true) && (pci.basic_info.use_time == false)) + PRINT_AND_THROW("A term is using time and basic_info is not set correctly. Try basic_info.use_time = true"); + + // This could be removed in the future once we are sure that all costs are + if ((use_time == false) && (pci.basic_info.use_time == true)) + PRINT_AND_THROW("No terms use time and basic_info is not set correctly. Try basic_info.use_time = false"); + + TrajOptProblemPtr prob(new TrajOptProblem(pci)); + + // Generate initial trajectory and check its size + robot_model::RobotModelConstPtr robot_model = pci.planning_scene->getRobotModel(); + robot_state::RobotState current_state = pci.planning_scene->getCurrentState(); + + const robot_state::JointModelGroup* joint_model_group = current_state.getJointModelGroup(pci.planning_group_name); + int n_dof = prob->GetNumDOF(); + + std::vector current_joint_values; + current_state.copyJointGroupPositions(joint_model_group, current_joint_values); + + trajopt::TrajArray init_traj; + generateInitialTrajectory(pci, current_joint_values, init_traj); + + if (pci.basic_info.use_time == true) + { + prob->SetHasTime(true); + if (init_traj.rows() != n_steps || init_traj.cols() != n_dof + 1) + { + PRINT_AND_THROW(boost::format("Initial trajectory is not the right size matrix\n" + "Expected %i rows (time steps) x %i columns (%i dof + 1 time column)\n" + "Got %i rows and %i columns") % + n_steps % (n_dof + 1) % n_dof % init_traj.rows() % init_traj.cols()); + } + } + else + { + prob->SetHasTime(false); + if (init_traj.rows() != n_steps || init_traj.cols() != n_dof) + { + PRINT_AND_THROW(boost::format("Initial trajectory is not the right size matrix\n" + "Expected %i rows (time steps) x %i columns\n" + "Got %i rows and %i columns") % + n_steps % n_dof % init_traj.rows() % init_traj.cols()); + } + } + prob->SetInitTraj(init_traj); + + trajopt::VarArray matrix_traj_vars_temp; + // If start_fixed, constrain the joint values for the first time step to be their initialized values + if (bi.start_fixed) + { + if (init_traj.rows() < 1) + { + PRINT_AND_THROW("Initial trajectory must contain at least the start state."); + } + + if (init_traj.cols() != (n_dof + (use_time ? 1 : 0))) + { + PRINT_AND_THROW("robot dof values don't match initialization. I don't " + "know what you want me to use for the dof values"); + } + + for (int j = 0; j < static_cast(n_dof); ++j) + { + matrix_traj_vars_temp = prob->GetVars(); + prob->addLinearConstraint(sco::exprSub(sco::AffExpr(matrix_traj_vars_temp(0, j)), init_traj(0, j)), sco::EQ); + } + } + + // Apply constraint to each fixed dof to its initial value for all timesteps (freeze that column) + if (!bi.dofs_fixed.empty()) + { + for (const int& dof_ind : bi.dofs_fixed) + { + for (int i = 1; i < prob->GetNumSteps(); ++i) + { + matrix_traj_vars_temp = prob->GetVars(); + prob->addLinearConstraint( + sco::exprSub(sco::AffExpr(matrix_traj_vars_temp(i, dof_ind)), sco::AffExpr(init_traj(0, dof_ind))), + sco::EQ); + } + } + } + + for (const TermInfoPtr& ci : pci.cost_infos) + { + ci->addObjectiveTerms(*prob); + } + + for (const TermInfoPtr& ci : pci.cnt_infos) + { + ci->addObjectiveTerms(*prob); + } + return prob; +} + +CartPoseTermInfo::CartPoseTermInfo() : TermInfo(TT_COST | TT_CNT) +{ + pos_coeffs = Eigen::Vector3d::Ones(); + rot_coeffs = Eigen::Vector3d::Ones(); + tcp.setIdentity(); +} + +void CartPoseTermInfo::addObjectiveTerms(TrajOptProblem& prob) +{ + unsigned int n_dof = prob.GetActiveGroupNumDOF(); + + Eigen::Isometry3d input_pose; + Eigen::Quaterniond q(wxyz(0), wxyz(1), wxyz(2), wxyz(3)); + input_pose.linear() = q.matrix(); + input_pose.translation() = xyz; + + if (term_type == (TT_COST | TT_USE_TIME)) + { + ROS_ERROR("Use time version of this term has not been defined."); + } + else if (term_type == (TT_CNT | TT_USE_TIME)) + { + ROS_ERROR("Use time version of this term has not been defined."); + } + else if ((term_type & TT_COST) && ~(term_type | ~TT_USE_TIME)) + { + sco::VectorOfVectorPtr f(new CartPoseErrCalculator(input_pose, prob.GetPlanningScene(), link, tcp)); + prob.addCost(sco::CostPtr(new sco::CostFromErrFunc(f, prob.GetVarRow(timestep, 0, n_dof), + concatVector(rot_coeffs, pos_coeffs), sco::ABS, name))); + } + else if ((term_type & TT_CNT) && ~(term_type | ~TT_USE_TIME)) + { + sco::VectorOfVectorPtr f(new CartPoseErrCalculator(input_pose, prob.GetPlanningScene(), link, tcp)); + prob.addConstraint(sco::ConstraintPtr(new sco::ConstraintFromErrFunc( + f, prob.GetVarRow(timestep, 0, n_dof), concatVector(rot_coeffs, pos_coeffs), sco::EQ, name))); + } + else + { + ROS_WARN("CartPoseTermInfo does not have a valid term_type defined. No cost/constraint applied"); + } +} + +void JointPoseTermInfo::addObjectiveTerms(TrajOptProblem& prob) +{ + unsigned int n_dof = prob.GetActiveGroupNumDOF(); + + // If optional parameter not given, set to default + if (coeffs.empty()) + coeffs = trajopt::DblVec(n_dof, 1); + if (upper_tols.empty()) + upper_tols = trajopt::DblVec(n_dof, 0); + if (lower_tols.empty()) + lower_tols = trajopt::DblVec(n_dof, 0); + if (last_step <= -1) + last_step = prob.GetNumSteps() - 1; + + // Check time step is valid + if ((prob.GetNumSteps() - 1) <= first_step) + first_step = prob.GetNumSteps() - 1; + if ((prob.GetNumSteps() - 1) <= last_step) + last_step = prob.GetNumSteps() - 1; + // if (last_step == first_step) + // last_step += 1; + if (last_step < first_step) + { + int tmp = first_step; + first_step = last_step; + last_step = tmp; + ROS_WARN("Last time step for JointPosTerm comes before first step. Reversing them."); + } + if (last_step == -1) // last_step not set + last_step = first_step; + + // Check if parameters are the correct size. + checkParameterSize(coeffs, n_dof, "JointPoseTermInfo coeffs", true); + checkParameterSize(targets, n_dof, "JointPoseTermInfo targets", true); + checkParameterSize(upper_tols, n_dof, "JointPoseTermInfo upper_tols", true); + checkParameterSize(lower_tols, n_dof, "JointPoseTermInfo lower_tols", true); + + // Check if tolerances are all zeros + bool is_upper_zeros = + std::all_of(upper_tols.begin(), upper_tols.end(), [](double i) { return util::doubleEquals(i, 0.); }); + bool is_lower_zeros = + std::all_of(lower_tols.begin(), lower_tols.end(), [](double i) { return util::doubleEquals(i, 0.); }); + + // Get vars associated with joints + trajopt::VarArray vars = prob.GetVars(); + trajopt::VarArray joint_vars = vars.block(0, 0, vars.rows(), static_cast(n_dof)); + if (prob.GetHasTime()) + ROS_INFO("JointPoseTermInfo does not differ based on setting of TT_USE_TIME"); + + if (term_type & TT_COST) + { + // If the tolerances are 0, an equality cost is set. Otherwise it's a hinged "inequality" cost + if (is_upper_zeros && is_lower_zeros) + { + prob.addCost(sco::CostPtr(new trajopt::JointPosEqCost(joint_vars, util::toVectorXd(coeffs), + util::toVectorXd(targets), first_step, last_step))); + prob.getCosts().back()->setName(name); + } + else + { + prob.addCost(sco::CostPtr(new trajopt::JointPosIneqCost(joint_vars, util::toVectorXd(coeffs), + util::toVectorXd(targets), util::toVectorXd(upper_tols), + util::toVectorXd(lower_tols), first_step, last_step))); + prob.getCosts().back()->setName(name); + } + } + else if (term_type & TT_CNT) + { + // If the tolerances are 0, an equality cnt is set. Otherwise it's an inequality constraint + if (is_upper_zeros && is_lower_zeros) + { + prob.addConstraint(sco::ConstraintPtr(new trajopt::JointPosEqConstraint( + joint_vars, util::toVectorXd(coeffs), util::toVectorXd(targets), first_step, last_step))); + prob.getConstraints().back()->setName(name); + } + else + { + prob.addConstraint(sco::ConstraintPtr(new trajopt::JointPosIneqConstraint( + joint_vars, util::toVectorXd(coeffs), util::toVectorXd(targets), util::toVectorXd(upper_tols), + util::toVectorXd(lower_tols), first_step, last_step))); + prob.getConstraints().back()->setName(name); + } + } + else + { + ROS_WARN("JointPosTermInfo does not have a valid term_type defined. No cost/constraint applied"); + } +} + +void JointVelTermInfo::addObjectiveTerms(TrajOptProblem& prob) +{ + unsigned int n_dof = prob.GetNumDOF(); + + // If optional parameter not given, set to default + if (coeffs.empty()) + coeffs = trajopt::DblVec(n_dof, 1); + if (upper_tols.empty()) + upper_tols = trajopt::DblVec(n_dof, 0); + if (lower_tols.empty()) + lower_tols = trajopt::DblVec(n_dof, 0); + if (last_step <= -1) + last_step = prob.GetNumSteps() - 1; + + // If only one time step is desired, calculate velocity with next step (2 steps are needed for 1 velocity calculation) + if ((prob.GetNumSteps() - 2) <= first_step) + first_step = prob.GetNumSteps() - 2; + if ((prob.GetNumSteps() - 1) <= last_step) + last_step = prob.GetNumSteps() - 1; + if (last_step == first_step) + last_step += 1; + if (last_step < first_step) + { + int tmp = first_step; + first_step = last_step; + last_step = tmp; + ROS_WARN("Last time step for JointVelTerm comes before first step. Reversing them."); + } + + // Check if parameters are the correct size. + checkParameterSize(coeffs, n_dof, "JointVelTermInfo coeffs", true); + checkParameterSize(targets, n_dof, "JointVelTermInfo targets", true); + checkParameterSize(upper_tols, n_dof, "JointVelTermInfo upper_tols", true); + checkParameterSize(lower_tols, n_dof, "JointVelTermInfo lower_tols", true); + assert(last_step > first_step); + assert(first_step >= 0); + + // Check if tolerances are all zeros + bool is_upper_zeros = + std::all_of(upper_tols.begin(), upper_tols.end(), [](double i) { return util::doubleEquals(i, 0.); }); + bool is_lower_zeros = + std::all_of(lower_tols.begin(), lower_tols.end(), [](double i) { return util::doubleEquals(i, 0.); }); + + // Get vars associated with joints + trajopt::VarArray vars = prob.GetVars(); + trajopt::VarArray joint_vars = vars.block(0, 0, vars.rows(), static_cast(n_dof)); + + if (term_type == (TT_COST | TT_USE_TIME)) + { + unsigned num_vels = last_step - first_step; + + // Apply seperate cost to each joint b/c that is how the error function is currently written + for (size_t j = 0; j < n_dof; j++) + { + // Get a vector of a single column of vars + sco::VarVector joint_vars_vec = joint_vars.cblock(first_step, j, last_step - first_step + 1); + sco::VarVector time_vars_vec = vars.cblock(first_step, vars.cols() - 1, last_step - first_step + 1); + + // If the tolerances are 0, an equality cost is set + if (is_upper_zeros && is_lower_zeros) + { + trajopt::DblVec single_jnt_coeffs = trajopt::DblVec(num_vels * 2, coeffs[j]); + prob.addCost(sco::CostPtr(new sco::CostFromErrFunc( + sco::VectorOfVectorPtr(new JointVelErrCalculator(targets[j], upper_tols[j], lower_tols[j])), + sco::MatrixOfVectorPtr(new JointVelJacobianCalculator()), concatVector(joint_vars_vec, time_vars_vec), + util::toVectorXd(single_jnt_coeffs), sco::SQUARED, name + "_j" + std::to_string(j)))); + } + // Otherwise it's a hinged "inequality" cost + else + { + trajopt::DblVec single_jnt_coeffs = trajopt::DblVec(num_vels * 2, coeffs[j]); + prob.addCost(sco::CostPtr(new sco::CostFromErrFunc( + sco::VectorOfVectorPtr(new JointVelErrCalculator(targets[j], upper_tols[j], lower_tols[j])), + sco::MatrixOfVectorPtr(new JointVelJacobianCalculator()), concatVector(joint_vars_vec, time_vars_vec), + util::toVectorXd(single_jnt_coeffs), sco::HINGE, name + "_j" + std::to_string(j)))); + } + } + } + else if (term_type == (TT_CNT | TT_USE_TIME)) + { + unsigned num_vels = last_step - first_step; + + // Apply seperate cnt to each joint b/c that is how the error function is currently written + for (size_t j = 0; j < n_dof; j++) + { + // Get a vector of a single column of vars + sco::VarVector joint_vars_vec = joint_vars.cblock(first_step, j, last_step - first_step + 1); + sco::VarVector time_vars_vec = vars.cblock(first_step, vars.cols() - 1, last_step - first_step + 1); + + // If the tolerances are 0, an equality cnt is set + if (is_upper_zeros && is_lower_zeros) + { + trajopt::DblVec single_jnt_coeffs = trajopt::DblVec(num_vels * 2, coeffs[j]); + prob.addConstraint(sco::ConstraintPtr(new sco::ConstraintFromErrFunc( + sco::VectorOfVectorPtr(new JointVelErrCalculator(targets[j], upper_tols[j], lower_tols[j])), + sco::MatrixOfVectorPtr(new JointVelJacobianCalculator()), concatVector(joint_vars_vec, time_vars_vec), + util::toVectorXd(single_jnt_coeffs), sco::EQ, name + "_j" + std::to_string(j)))); + } + // Otherwise it's a hinged "inequality" constraint + else + { + trajopt::DblVec single_jnt_coeffs = trajopt::DblVec(num_vels * 2, coeffs[j]); + prob.addConstraint(sco::ConstraintPtr(new sco::ConstraintFromErrFunc( + sco::VectorOfVectorPtr(new JointVelErrCalculator(targets[j], upper_tols[j], lower_tols[j])), + sco::MatrixOfVectorPtr(new JointVelJacobianCalculator()), concatVector(joint_vars_vec, time_vars_vec), + util::toVectorXd(single_jnt_coeffs), sco::INEQ, name + "_j" + std::to_string(j)))); + } + } + } + else if ((term_type & TT_COST) && ~(term_type | ~TT_USE_TIME)) + { + // If the tolerances are 0, an equality cost is set. Otherwise it's a hinged "inequality" cost + if (is_upper_zeros && is_lower_zeros) + { + prob.addCost(sco::CostPtr(new trajopt::JointVelEqCost(joint_vars, util::toVectorXd(coeffs), + util::toVectorXd(targets), first_step, last_step))); + prob.getCosts().back()->setName(name); + } + else + { + prob.addCost(sco::CostPtr(new trajopt::JointVelIneqCost(joint_vars, util::toVectorXd(coeffs), + util::toVectorXd(targets), util::toVectorXd(upper_tols), + util::toVectorXd(lower_tols), first_step, last_step))); + prob.getCosts().back()->setName(name); + } + } + else if ((term_type & TT_CNT) && ~(term_type | ~TT_USE_TIME)) + { + // If the tolerances are 0, an equality cnt is set. Otherwise it's an inequality constraint + if (is_upper_zeros && is_lower_zeros) + { + prob.addConstraint(sco::ConstraintPtr(new trajopt::JointVelEqConstraint( + joint_vars, util::toVectorXd(coeffs), util::toVectorXd(targets), first_step, last_step))); + prob.getConstraints().back()->setName(name); + } + else + { + prob.addConstraint(sco::ConstraintPtr(new trajopt::JointVelIneqConstraint( + joint_vars, util::toVectorXd(coeffs), util::toVectorXd(targets), util::toVectorXd(upper_tols), + util::toVectorXd(lower_tols), first_step, last_step))); + prob.getConstraints().back()->setName(name); + } + } + else + { + ROS_WARN("JointVelTermInfo does not have a valid term_type defined. No cost/constraint applied"); + } +} + +void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, + trajopt::TrajArray& init_traj) +{ + Eigen::VectorXd current_pos(current_joint_values.size()); + for (int joint_index = 0; joint_index < current_joint_values.size(); ++joint_index) + { + current_pos(joint_index) = current_joint_values[joint_index]; + } + + InitInfo init_info = pci.init_info; + + // initialize based on type specified + if (init_info.type == InitInfo::STATIONARY) + { + // Initializes all joint values to the initial value (the current value in scene) + init_traj = current_pos.transpose().replicate(pci.basic_info.n_steps, 1); + } + else if (init_info.type == InitInfo::JOINT_INTERPOLATED) + { + // Linearly interpolates between initial value (current values in the scene) and the joint position specified in + // InitInfo.data + Eigen::VectorXd end_pos = init_info.data; + init_traj.resize(pci.basic_info.n_steps, end_pos.rows()); + for (int dof_index = 0; dof_index < current_pos.rows(); ++dof_index) + { + init_traj.col(dof_index) = + Eigen::VectorXd::LinSpaced(pci.basic_info.n_steps, current_pos(dof_index), end_pos(dof_index)); + } + } + else if (init_info.type == InitInfo::GIVEN_TRAJ) + { + // Initializes the matrix to a given trajectory + init_traj = init_info.data; + } + else + { + PRINT_AND_THROW("Init Info did not have a valid type. Valid types are " + "STATIONARY, JOINT_INTERPOLATED, or GIVEN_TRAJ"); + } + + // Currently all trajectories are generated without time then appended here + if (pci.basic_info.use_time) + { + // add on time (default to 1 sec) + init_traj.conservativeResize(Eigen::NoChange_t(), init_traj.cols() + 1); + + init_traj.block(0, init_traj.cols() - 1, init_traj.rows(), 1) = + Eigen::VectorXd::Constant(init_traj.rows(), init_info.dt); + } +} +} diff --git a/moveit_planners/trajopt/src/trajopt_interface.cpp b/moveit_planners/trajopt/src/trajopt_interface.cpp new file mode 100644 index 0000000000..4f76c1add2 --- /dev/null +++ b/moveit_planners/trajopt/src/trajopt_interface.cpp @@ -0,0 +1,463 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, PickNik, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Omid Heidari */ + +#include +#include + +#include + +#include +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include + +#include "trajopt_interface/trajopt_interface.h" +#include "trajopt_interface/problem_description.h" + +namespace trajopt_interface +{ +TrajOptInterface::TrajOptInterface(const ros::NodeHandle& nh) : nh_(nh), name_("TrajOptInterface") +{ + trajopt_problem_ = TrajOptProblemPtr(new TrajOptProblem); + setDefaultTrajOPtParams(); + + // TODO: callbacks should be defined by the user + optimizer_callbacks_.push_back(callBackFunc); +} + +bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planning_scene, + const planning_interface::MotionPlanRequest& req, + moveit_msgs::MotionPlanDetailedResponse& res) +{ + ROS_INFO(" ======================================= From trajopt_interface, solve is called"); + setTrajOptParams(params_); + + if (!planning_scene) + { + ROS_ERROR_STREAM_NAMED(name_, "No planning scene initialized."); + res.error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE; + return false; + } + + ROS_INFO(" ======================================= Extract current state information"); + ros::WallTime start_time = ros::WallTime::now(); + robot_model::RobotModelConstPtr robot_model = planning_scene->getRobotModel(); + bool robot_model_ok = static_cast(robot_model); + if (!robot_model_ok) + ROS_ERROR_STREAM_NAMED(name_, "robot model is not loaded properly"); + robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model)); + *current_state = planning_scene->getCurrentState(); + const robot_state::JointModelGroup* joint_model_group = current_state->getJointModelGroup(req.group_name); + if (joint_model_group == nullptr) + ROS_ERROR_STREAM_NAMED(name_, "joint model group is empty"); + std::vector group_joint_names = joint_model_group->getActiveJointModelNames(); + int dof = group_joint_names.size(); + std::vector current_joint_values; + current_state->copyJointGroupPositions(joint_model_group, current_joint_values); + + // Current state is different from star state in general + ROS_INFO(" ======================================= Extract start state infromation"); + trajopt::DblVec start_joint_values = extractStartJointValues(req, group_joint_names); + + // check the start state for being empty or joint limit violiation + if (start_joint_values.empty()) + { + ROS_ERROR_STREAM_NAMED(name_, "Start_state is empty"); + res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE; + return false; + } + + if (not joint_model_group->satisfiesPositionBounds(start_joint_values.data())) + { + ROS_ERROR_STREAM_NAMED(name_, "Start state violates joint limits"); + res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_ROBOT_STATE; + return false; + } + + ROS_INFO(" ======================================= Create ProblemInfo"); + ProblemInfo problem_info(planning_scene, req.group_name); + + setProblemInfoParam(problem_info); + + ROS_INFO(" ======================================= Populate init info, hard-coded"); + // TODO: init info should be defined by user. To this end, we need to add seed trajectories to MotionPlanRequest. + // JOINT_INTERPOLATED: data is the current joint values + // GIVEN_TRAJ: data is the joint values of the current state copied to all timesteps + Eigen::VectorXd current_joint_values_eigen(dof); + for (int joint_index = 0; joint_index < dof; ++joint_index) + { + current_joint_values_eigen(joint_index) = current_joint_values[joint_index]; + } + + if (problem_info.init_info.type == InitInfo::JOINT_INTERPOLATED) + { + problem_info.init_info.data = current_joint_values_eigen; + } + else if (problem_info.init_info.type == InitInfo::GIVEN_TRAJ) + { + problem_info.init_info.data = current_joint_values_eigen.transpose().replicate(problem_info.basic_info.n_steps, 1); + } + + ROS_INFO(" ======================================= Create Constraints"); + if (req.goal_constraints.empty()) + { + ROS_ERROR_STREAM_NAMED("trajopt_planner", "No goal constraints specified!"); + res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS; + return false; + } + + ROS_INFO(" ======================================= Cartesian Constraints"); + if (!req.goal_constraints[0].position_constraints.empty() && !req.goal_constraints[0].orientation_constraints.empty()) + { + CartPoseTermInfoPtr cart_goal_pos(new CartPoseTermInfo); + + // TODO: Feed cart_goal_pos with request information and the needed param to the setup.yaml file + // TODO: Multiple Cartesian constraints + + // Add the constraint to problem_info + problem_info.cnt_infos.push_back(cart_goal_pos); + } + else if (req.goal_constraints[0].position_constraints.empty() && + !req.goal_constraints[0].orientation_constraints.empty()) + { + ROS_ERROR_STREAM_NAMED("trajopt_planner", "position constraint is not defined"); + res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS; + return false; + } + else if (!req.goal_constraints[0].orientation_constraints.empty() && + req.goal_constraints[0].orientation_constraints.empty()) + { + ROS_ERROR_STREAM_NAMED("trajopt_planner", "orientation constraint is not defined"); + res.error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS; + return false; + } + + ROS_INFO(" ======================================= Constraints from request goal_constraints"); + for (auto goal_cnt : req.goal_constraints) + { + JointPoseTermInfoPtr joint_pos_term(new JointPoseTermInfo); + // When using MotionPlanning Display in RViz, the created request has no name for the constriant + setJointPoseTermInfoParams(joint_pos_term, (goal_cnt.name != "") ? goal_cnt.name : "goal_tmp"); + + trajopt::DblVec joint_goal_constraints; + for (const moveit_msgs::JointConstraint& joint_goal_constraint : goal_cnt.joint_constraints) + { + joint_goal_constraints.push_back(joint_goal_constraint.position); + } + joint_pos_term->targets = joint_goal_constraints; + problem_info.cnt_infos.push_back(joint_pos_term); + } + + ROS_INFO(" ======================================= Constraints from request start_state"); + // add the start pos from request as a constraint + JointPoseTermInfoPtr joint_start_pos(new JointPoseTermInfo); + + joint_start_pos->targets = start_joint_values; + setJointPoseTermInfoParams(joint_start_pos, "start_pos"); + problem_info.cnt_infos.push_back(joint_start_pos); + + ROS_INFO(" ======================================= Velocity Constraints, hard-coded"); + // TODO: should be defined by user, its parametes should be added to setup.yaml + JointVelTermInfoPtr joint_vel(new JointVelTermInfo); + + joint_vel->coeffs = std::vector(dof, 5.0); + joint_vel->targets = std::vector(dof, 0.0); + joint_vel->first_step = 0; + joint_vel->last_step = problem_info.basic_info.n_steps - 1; + joint_vel->name = "joint_vel"; + joint_vel->term_type = trajopt_interface::TT_COST; + problem_info.cost_infos.push_back(joint_vel); + + ROS_INFO(" ======================================= Visibility Constraints"); + if (!req.goal_constraints[0].visibility_constraints.empty()) + { + // TODO: Add visibility constraint + } + + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.improve_ratio_threshold: " << params_.improve_ratio_threshold); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.min_trust_box_size: " << params_.min_trust_box_size); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.min_approx_improve: " << params_.min_approx_improve); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.params_.min_approx_improve_frac: " << params_.min_approx_improve_frac); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.max_iter: " << params_.max_iter); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.trust_shrink_ratio: " << params_.trust_shrink_ratio); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.trust_expand_ratio: " << params_.trust_expand_ratio); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.cnt_tolerance: " << params_.cnt_tolerance); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.max_merit_coeff_increases: " << params_.max_merit_coeff_increases); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.merit_coeff_increase_ratio: " << params_.merit_coeff_increase_ratio); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.max_time: " << params_.max_time); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.merit_error_coeff: " << params_.merit_error_coeff); + ROS_DEBUG_STREAM_NAMED(name_, "trajopt_param.trust_box_size: " << params_.trust_box_size); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.n_steps: " << problem_info.basic_info.n_steps); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.dt_upper_lim: " << problem_info.basic_info.dt_upper_lim); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.dt_lower_lim: " << problem_info.basic_info.dt_lower_lim); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.start_fixed: " << problem_info.basic_info.start_fixed); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.use_time: " << problem_info.basic_info.use_time); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.convex_solver: " << problem_info.basic_info.convex_solver); + + std::string problem_info_type; + switch (problem_info.init_info.type) + { + case InitInfo::STATIONARY: + problem_info_type = "STATIONARY"; + break; + case InitInfo::JOINT_INTERPOLATED: + problem_info_type = "JOINT_INTERPOLATED"; + break; + case InitInfo::GIVEN_TRAJ: + problem_info_type = "GIVEN_TRAJ"; + break; + } + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.type: " << problem_info_type); + ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.dt: " << problem_info.init_info.dt); + + ROS_INFO(" ======================================= Construct problem"); + trajopt_problem_ = ConstructProblem(problem_info); + + ROS_INFO_STREAM_NAMED("num_cost", trajopt_problem_->getNumCosts()); + ROS_INFO_STREAM_NAMED("num_constraints", trajopt_problem_->getNumConstraints()); + + ROS_INFO(" ======================================= TrajOpt Optimization"); + sco::BasicTrustRegionSQP opt(trajopt_problem_); + + opt.setParameters(params_); + opt.initialize(trajopt::trajToDblVec(trajopt_problem_->GetInitTraj())); + + // Add all callbacks + for (const sco::Optimizer::Callback& callback : optimizer_callbacks_) + { + opt.addCallback(callback); + } + + // Optimize + ros::WallTime create_time = ros::WallTime::now(); + opt.optimize(); + + ROS_INFO(" ======================================= TrajOpt Solution"); + trajopt::TrajArray opt_solution = trajopt::getTraj(opt.x(), trajopt_problem_->GetVars()); + + // assume that the trajectory is now optimized, fill in the output structure: + ROS_INFO_STREAM_NAMED("num_rows", opt_solution.rows()); + ROS_INFO_STREAM_NAMED("num_cols", opt_solution.cols()); + + res.trajectory.resize(1); + res.trajectory[0].joint_trajectory.joint_names = group_joint_names; + res.trajectory[0].joint_trajectory.header = req.start_state.joint_state.header; + + // fill in the entire trajectory + res.trajectory[0].joint_trajectory.points.resize(opt_solution.rows()); + for (int i = 0; i < opt_solution.rows(); i++) + { + res.trajectory[0].joint_trajectory.points[i].positions.resize(opt_solution.cols()); + for (size_t j = 0; j < opt_solution.cols(); j++) + { + res.trajectory[0].joint_trajectory.points[i].positions[j] = opt_solution(i, j); + } + // Further filtering is required to set valid timestamps accounting for velocity and acceleration constraints. + res.trajectory[0].joint_trajectory.points[i].time_from_start = ros::Duration(0.0); + } + + res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + res.processing_time.push_back((ros::WallTime::now() - start_time).toSec()); + + ROS_INFO(" ======================================= check if final state is within goal tolerances"); + kinematic_constraints::JointConstraint joint_cnt(planning_scene->getRobotModel()); + robot_state::RobotState last_state(*current_state); + last_state.setJointGroupPositions(req.group_name, res.trajectory[0].joint_trajectory.points.back().positions); + + for (int jn = 0; jn < res.trajectory[0].joint_trajectory.points.back().positions.size(); ++jn) + { + ROS_INFO_STREAM_NAMED("joint_value", res.trajectory[0].joint_trajectory.points.back().positions[jn] + << " " << req.goal_constraints.back().joint_constraints[jn].position); + } + + bool constraints_are_ok = true; + int joint_cnt_index = 0; + for (const moveit_msgs::JointConstraint& constraint : req.goal_constraints.back().joint_constraints) + { + ROS_INFO("index %i: jc.configure(constraint)=> %d, jc.decide(last_state).satisfied=> %d, tolerance %f", + joint_cnt_index, joint_cnt.configure(constraint), joint_cnt.decide(last_state).satisfied, + constraint.tolerance_above); + constraints_are_ok = constraints_are_ok and joint_cnt.configure(constraint); + constraints_are_ok = constraints_are_ok and joint_cnt.decide(last_state).satisfied; + if (not constraints_are_ok) + { + ROS_ERROR_STREAM_NAMED("trajopt_planner", "Goal constraints are violated: " << constraint.joint_name); + res.error_code.val = moveit_msgs::MoveItErrorCodes::GOAL_CONSTRAINTS_VIOLATED; + return false; + } + joint_cnt_index = joint_cnt_index + 1; + } + + ROS_INFO(" ==================================== Response"); + res.trajectory_start = req.start_state; + + ROS_INFO(" ==================================== Debug Response"); + ROS_INFO_STREAM_NAMED("group_name", res.group_name); + ROS_INFO_STREAM_NAMED("start_traj_name_size", res.trajectory_start.joint_state.name.size()); + ROS_INFO_STREAM_NAMED("start_traj_position_size", res.trajectory_start.joint_state.position.size()); + ROS_INFO_STREAM_NAMED("traj_name_size", res.trajectory[0].joint_trajectory.joint_names.size()); + ROS_INFO_STREAM_NAMED("traj_point_size", res.trajectory[0].joint_trajectory.points.size()); + return true; +} + +void TrajOptInterface::setDefaultTrajOPtParams() +{ + sco::BasicTrustRegionSQPParameters params; + params_ = params; +} + +void TrajOptInterface::setTrajOptParams(sco::BasicTrustRegionSQPParameters& params) +{ + nh_.param("trajopt_param/improve_ratio_threshold", params.improve_ratio_threshold, 0.25); + nh_.param("trajopt_param/min_trust_box_size", params.min_trust_box_size, 1e-4); + nh_.param("trajopt_param/min_approx_improve", params.min_approx_improve, 1e-4); + nh_.param("trajopt_param/min_approx_improve_frac", params.min_approx_improve_frac, -static_cast(INFINITY)); + nh_.param("trajopt_param/max_iter", params.max_iter, 100.0); + nh_.param("trajopt_param/trust_shrink_ratio", params.trust_shrink_ratio, 0.1); + + nh_.param("trajopt_param/trust_expand_ratio", params.trust_expand_ratio, 1.5); + nh_.param("trajopt_param/cnt_tolerance", params.cnt_tolerance, 1e-4); + nh_.param("trajopt_param/max_merit_coeff_increases", params.max_merit_coeff_increases, 5.0); + nh_.param("trajopt_param/merit_coeff_increase_ratio", params.merit_coeff_increase_ratio, 10.0); + nh_.param("trajopt_param/max_time", params.max_time, static_cast(INFINITY)); + nh_.param("trajopt_param/merit_error_coeff", params.merit_error_coeff, 10.0); + nh_.param("trajopt_param/trust_box_size", params.trust_box_size, 1e-1); +} + +void TrajOptInterface::setProblemInfoParam(ProblemInfo& problem_info) +{ + nh_.param("problem_info/basic_info/n_steps", problem_info.basic_info.n_steps, 20); + nh_.param("problem_info/basic_info/dt_upper_lim", problem_info.basic_info.dt_upper_lim, 2.0); + nh_.param("problem_info/basic_info/dt_lower_lim", problem_info.basic_info.dt_lower_lim, 100.0); + nh_.param("problem_info/basic_info/start_fixed", problem_info.basic_info.start_fixed, true); + nh_.param("problem_info/basic_info/use_time", problem_info.basic_info.use_time, false); + int convex_solver_index; + nh_.param("problem_info/basic_info/convex_solver", convex_solver_index, 1); + switch (convex_solver_index) + { + case 1: + problem_info.basic_info.convex_solver = sco::ModelType::AUTO_SOLVER; + break; + case 2: + problem_info.basic_info.convex_solver = sco::ModelType::BPMPD; + break; + case 3: + problem_info.basic_info.convex_solver = sco::ModelType::OSQP; + break; + case 4: + problem_info.basic_info.convex_solver = sco::ModelType::QPOASES; + break; + case 5: + problem_info.basic_info.convex_solver = sco::ModelType::GUROBI; + break; + } + + nh_.param("problem_info/init_info/dt", problem_info.init_info.dt, 0.5); + int type_index; + nh_.param("problem_info/init_info/type", type_index, 1); + switch (type_index) + { + case 1: + problem_info.init_info.type = InitInfo::STATIONARY; + break; + case 2: + problem_info.init_info.type = InitInfo::JOINT_INTERPOLATED; + break; + case 3: + problem_info.init_info.type = InitInfo::GIVEN_TRAJ; + break; + } +} + +void TrajOptInterface::setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name) +{ + int term_type_index; + std::string term_type_address = "joint_pos_term_info/" + name + "/term_type"; + nh_.param(term_type_address, term_type_index, 1); + + switch (term_type_index) + { + case 1: + jp->term_type = TT_COST; + break; + case 2: + jp->term_type = TT_CNT; + break; + case 3: + jp->term_type = TT_USE_TIME; + break; + } + + nh_.getParam("joint_pos_term_info/" + name + "/first_timestep", jp->first_step); + nh_.getParam("joint_pos_term_info/" + name + "/last_timestep", jp->last_step); + nh_.getParam("joint_pos_term_info/" + name + "/name", jp->name); +} + +trajopt::DblVec TrajOptInterface::extractStartJointValues(const planning_interface::MotionPlanRequest& req, + const std::vector& group_joint_names) +{ + std::unordered_map all_joints; + trajopt::DblVec start_joint_vals; + + for (int joint_index = 0; joint_index < req.start_state.joint_state.position.size(); ++joint_index) + { + all_joints[req.start_state.joint_state.name[joint_index]] = req.start_state.joint_state.position[joint_index]; + } + + for (auto joint_name : group_joint_names) + { + ROS_INFO(" joint position from start state, name: %s, value: %f", joint_name.c_str(), all_joints[joint_name]); + start_joint_vals.push_back(all_joints[joint_name]); + } + + return start_joint_vals; +} + +void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res) +{ + // TODO: Create the actuall implementation +} + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/src/trajopt_planner_manager.cpp b/moveit_planners/trajopt/src/trajopt_planner_manager.cpp new file mode 100644 index 0000000000..760c58f823 --- /dev/null +++ b/moveit_planners/trajopt/src/trajopt_planner_manager.cpp @@ -0,0 +1,141 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, PickNik LLC + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of PickNik LLC nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Omid Heidari + Desc: TrajOpt planning plugin +*/ + +#include + +#include "moveit/collision_detection_fcl/collision_detector_allocator_fcl.h" + +#include + +#include "trajopt_interface/trajopt_planning_context.h" + +namespace trajopt_interface +{ +class TrajOptPlannerManager : public planning_interface::PlannerManager +{ +public: + TrajOptPlannerManager() : planning_interface::PlannerManager() + { + } + + bool initialize(const robot_model::RobotModelConstPtr& model, const std::string& ns) override + { + ROS_INFO(" ======================================= initialize gets called"); + + if (!ns.empty()) + nh_ = ros::NodeHandle(ns); + std::string trajopt_ns = ns.empty() ? "trajopt" : ns + "/trajopt"; + + for (const std::string& gpName : model->getJointModelGroupNames()) + { + ROS_INFO(" ======================================= group name: %s, robot model: %s", gpName.c_str(), + model->getName().c_str()); + planning_contexts_[gpName] = + TrajOptPlanningContextPtr(new TrajOptPlanningContext("trajopt_planning_context", gpName, model)); + } + + return true; + } + + bool canServiceRequest(const moveit_msgs::MotionPlanRequest& req) const override + { + return req.trajectory_constraints.constraints.empty(); + } + + std::string getDescription() const override + { + return "TrajOpt"; + } + + void getPlanningAlgorithms(std::vector& algs) const override + { + algs.clear(); + algs.push_back("trajopt"); + } + + planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr& planning_scene, + const planning_interface::MotionPlanRequest& req, + moveit_msgs::MoveItErrorCodes& error_code) const override + { + ROS_INFO(" ======================================= getPlanningContext() is called "); + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + + if (req.group_name.empty()) + { + ROS_ERROR("No group specified to plan for"); + error_code.val = moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME; + return planning_interface::PlanningContextPtr(); + } + + if (!planning_scene) + { + ROS_ERROR("No planning scene supplied as input"); + error_code.val = moveit_msgs::MoveItErrorCodes::FAILURE; + return planning_interface::PlanningContextPtr(); + } + + // create PlanningScene using hybrid collision detector + planning_scene::PlanningScenePtr ps = planning_scene->diff(); + + // set FCL for the collision + ps->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create(), true); + + // retrieve and configure existing context + const TrajOptPlanningContextPtr& context = planning_contexts_.at(req.group_name); + + ROS_INFO(" ======================================= context is made "); + + context->setPlanningScene(ps); + context->setMotionPlanRequest(req); + + error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS; + + return context; + } + +private: + ros::NodeHandle nh_; + +protected: + std::map planning_contexts_; +}; + +} // namespace trajopt_interface + +// register the TrajOptPlannerManager class as a plugin +CLASS_LOADER_REGISTER_CLASS(trajopt_interface::TrajOptPlannerManager, planning_interface::PlannerManager); diff --git a/moveit_planners/trajopt/src/trajopt_planning_context.cpp b/moveit_planners/trajopt/src/trajopt_planning_context.cpp new file mode 100644 index 0000000000..34b1e4c307 --- /dev/null +++ b/moveit_planners/trajopt/src/trajopt_planning_context.cpp @@ -0,0 +1,76 @@ +#include +#include +#include +#include + +#include + +#include + +#include "trajopt_interface/trajopt_planning_context.h" +#include "trajopt_interface/trajopt_interface.h" + +namespace trajopt_interface +{ +TrajOptPlanningContext::TrajOptPlanningContext(const std::string& context_name, const std::string& group_name, + const robot_model::RobotModelConstPtr& model) + : planning_interface::PlanningContext(context_name, group_name), robot_model_(model) +{ + ROS_INFO(" ======================================= TrajOptPlanningContext is constructed"); + trajopt_interface_ = TrajOptInterfacePtr(new TrajOptInterface()); +} + +bool TrajOptPlanningContext::solve(planning_interface::MotionPlanDetailedResponse& res) +{ + moveit_msgs::MotionPlanDetailedResponse res_msg; + bool trajopt_solved = trajopt_interface_->solve(planning_scene_, request_, res_msg); + + if (trajopt_solved) + { + res.trajectory_.resize(1); + res.trajectory_[0] = + robot_trajectory::RobotTrajectoryPtr(new robot_trajectory::RobotTrajectory(robot_model_, getGroupName())); + + moveit::core::RobotState start_state(robot_model_); + robot_state::robotStateMsgToRobotState(res_msg.trajectory_start, start_state); + res.trajectory_[0]->setRobotTrajectoryMsg(start_state, res_msg.trajectory[0]); + + res.description_.push_back("plan"); + // TODO: Add the initial trajectory to res (MotionPlanDetailedResponse) + res.processing_time_ = res_msg.processing_time; + res.error_code_ = res_msg.error_code; + return true; + } + else + { + res.error_code_ = res_msg.error_code; + return false; + } +} + +bool TrajOptPlanningContext::solve(planning_interface::MotionPlanResponse& res) +{ + planning_interface::MotionPlanDetailedResponse res_detailed; + bool planning_success = solve(res_detailed); + + res.error_code_ = res_detailed.error_code_; + + if (planning_success) + { + res.trajectory_ = res_detailed.trajectory_[0]; + res.planning_time_ = res_detailed.processing_time_[0]; + } + + return planning_success; +} + +bool TrajOptPlanningContext::terminate() +{ + ROS_ERROR_STREAM_NAMED("trajopt_planning_context", "TrajOpt is not interruptable yet"); + return false; +} +void TrajOptPlanningContext::clear() +{ +} + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/test/trajectory_test.cpp b/moveit_planners/trajopt/test/trajectory_test.cpp new file mode 100644 index 0000000000..3494ba2d9e --- /dev/null +++ b/moveit_planners/trajopt/test/trajectory_test.cpp @@ -0,0 +1,212 @@ +/********************************************************************* + * Software License Agreement + * + * Copyright (c) 2019, PickNik Consulting + * All rights reserved. + * + *********************************************************************/ + +/* Author: Omid Heidari + Desc: Test the trajectory planned by trajopt + */ + +// C++ +#include +#include +#include + +// ROS +#include + +// Testing +#include + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include + +class TrajectoryTest : public ::testing::Test +{ +public: + TrajectoryTest() + { + } + +protected: + void SetUp() override + { + node_handle_ = ros::NodeHandle("~"); + robot_model_ = moveit::core::loadTestingRobotModel("panda"); + bool robot_model_ok_ = static_cast(robot_model_); + if (!robot_model_ok_) + ROS_ERROR_STREAM_NAMED("trajectory_test", "robot model is not loaded correctly"); + } + +protected: + robot_model::RobotModelPtr robot_model_; + std::vector group_joint_names_; + const std::string PLANNING_GROUP = "panda_arm"; + const double GOAL_TOLERANCE = 0.1; + ros::NodeHandle node_handle_; +}; // class TrajectoryTest + +TEST_F(TrajectoryTest, concatVectorValidation) +{ + std::vector vec_a = { 1, 2, 3, 4, 5 }; + std::vector vec_b = { 6, 7, 8, 9, 10 }; + std::vector vec_c = trajopt_interface::concatVector(vec_a, vec_b); + EXPECT_EQ(vec_c.size(), vec_a.size() + vec_b.size()); + + // Check if the output of concatVector is correct. + // Loop over the output and the input vectors to see if they match + std::size_t length_ab = vec_a.size() + vec_b.size(); + for (std::size_t index = 0; index < length_ab; ++index) + { + if (index < vec_a.size()) + { + EXPECT_EQ(vec_c[index], vec_a[index]); + } + else + { + EXPECT_EQ(vec_c[index], vec_b[index - vec_a.size()]); + } + } +} + +TEST_F(TrajectoryTest, goalTolerance) +{ + const std::string NODE_NAME = "trajectory_test"; + + // Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group + robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model_)); + current_state->setToDefaultValues(); + + const robot_state::JointModelGroup* joint_model_group = current_state->getJointModelGroup(PLANNING_GROUP); + EXPECT_NE(joint_model_group, nullptr); + const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); + EXPECT_EQ(joint_names.size(), 7); + + planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model_)); + + // Create response and request + planning_interface::MotionPlanRequest req; + planning_interface::MotionPlanResponse res; + + // Set start state + // ====================================================================================== + std::vector start_joint_values = { 0.4, 0.3, 0.5, -0.55, 0.88, 1.0, -0.075 }; + robot_state::RobotStatePtr start_state(new robot_state::RobotState(robot_model_)); + start_state->setJointGroupPositions(joint_model_group, start_joint_values); + start_state->update(); + + req.start_state.joint_state.name = joint_names; + req.start_state.joint_state.position = start_joint_values; + req.goal_constraints.clear(); + req.group_name = PLANNING_GROUP; + + // Set the goal state and joints tolerance + // ======================================================================================== + robot_state::RobotStatePtr goal_state(new robot_state::RobotState(robot_model_)); + std::vector goal_joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1 }; + goal_state->setJointGroupPositions(joint_model_group, goal_joint_values); + goal_state->update(); + moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(*goal_state, joint_model_group); + req.goal_constraints.push_back(joint_goal); + req.goal_constraints[0].name = "goal_pos"; + // Set joint tolerance + std::vector goal_joint_constraint = req.goal_constraints[0].joint_constraints; + for (std::size_t x = 0; x < goal_joint_constraint.size(); ++x) + { + req.goal_constraints[0].joint_constraints[x].tolerance_above = 0.001; + req.goal_constraints[0].joint_constraints[x].tolerance_below = 0.001; + } + + // Load planner + // ====================================================================================== + // We will now construct a loader to load a planner, by name. + // Note that we are using the ROS pluginlib library here. + boost::scoped_ptr> planner_plugin_loader; + planning_interface::PlannerManagerPtr planner_instance; + + std::string planner_plugin_name = "trajopt_interface/TrajOptPlanner"; + node_handle_.setParam("planning_plugin", planner_plugin_name); + + // Make sure the planner plugin is loaded + EXPECT_TRUE(node_handle_.getParam("planning_plugin", planner_plugin_name)); + try + { + planner_plugin_loader.reset(new pluginlib::ClassLoader( + "moveit_core", "planning_interface::PlannerManager")); + } + catch (pluginlib::PluginlibException& ex) + { + ROS_FATAL_STREAM_NAMED(NODE_NAME, "Exception while creating planning plugin loader " << ex.what()); + } + try + { + planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); + if (!planner_instance->initialize(robot_model_, node_handle_.getNamespace())) + ROS_FATAL_STREAM_NAMED(NODE_NAME, "Could not initialize planner instance"); + ROS_INFO_STREAM_NAMED(NODE_NAME, "Using planning interface '" << planner_instance->getDescription() << "'"); + } + catch (pluginlib::PluginlibException& ex) + { + const std::vector& classes = planner_plugin_loader->getDeclaredClasses(); + std::stringstream ss; + for (std::size_t i = 0; i < classes.size(); ++i) + ss << classes[i] << " "; + ROS_ERROR_STREAM_NAMED(NODE_NAME, "Exception while loading planner '" << planner_plugin_name << "': " << ex.what() + << std::endl + << "Available plugins: " << ss.str()); + } + + // Creat planning context + // ======================================================================================== + planning_interface::PlanningContextPtr context = + planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + + context->solve(res); + EXPECT_EQ(res.error_code_.val, res.error_code_.SUCCESS); + + moveit_msgs::MotionPlanResponse response; + res.getMessage(response); + + // Check the difference between the last step in the solution and the goal + // ======================================================================================== + std::vector joints_values_last_step = response.trajectory.joint_trajectory.points.back().positions; + + for (std::size_t joint_index = 0; joint_index < joints_values_last_step.size(); ++joint_index) + { + double goal_error = + abs(joints_values_last_step[joint_index] - req.goal_constraints[0].joint_constraints[joint_index].position); + std::cerr << "goal_error: " << goal_error << std::endl; + EXPECT_LT(goal_error, GOAL_TOLERANCE); + } +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "trajectory_test"); + + ros::AsyncSpinner spinner(1); + spinner.start(); + + int result = RUN_ALL_TESTS(); + ros::shutdown(); + + return result; +} diff --git a/moveit_planners/trajopt/test/trajectory_test.test b/moveit_planners/trajopt/test/trajectory_test.test new file mode 100644 index 0000000000..36314b49b5 --- /dev/null +++ b/moveit_planners/trajopt/test/trajectory_test.test @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/moveit_planners/trajopt/trajopt_interface_plugin_description.xml b/moveit_planners/trajopt/trajopt_interface_plugin_description.xml new file mode 100644 index 0000000000..051864285a --- /dev/null +++ b/moveit_planners/trajopt/trajopt_interface_plugin_description.xml @@ -0,0 +1,7 @@ + + + + The trajopt motion planner plugin which implements sequential convex optimization to solve motion planning problem. + + + diff --git a/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/run_benchmark_trajopt.launch b/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/run_benchmark_trajopt.launch new file mode 100644 index 0000000000..7185681292 --- /dev/null +++ b/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/run_benchmark_trajopt.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/trajopt_planning_pipeline.launch.xml b/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/trajopt_planning_pipeline.launch.xml new file mode 100644 index 0000000000..cf5735429d --- /dev/null +++ b/moveit_setup_assistant/templates/moveit_config_pkg_template/launch/trajopt_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + From 590a9c36d80ab55882d77f4c349c6344680a499b Mon Sep 17 00:00:00 2001 From: Felix von Drigalski Date: Fri, 16 Aug 2019 02:56:56 +0200 Subject: [PATCH 35/96] Add parameter to get_jacobian_matrix (#1595) * Add parameter to getJacobian Python interface * Add changes * Overload wrapper * Add test for reference_point_position * cleanup --- .../src/moveit_commander/move_group.py | 4 ++-- .../src/wrap_python_move_group.cpp | 20 +++++++++++++++---- .../test/python_move_group.py | 7 +++++++ 3 files changed, 25 insertions(+), 6 deletions(-) diff --git a/moveit_commander/src/moveit_commander/move_group.py b/moveit_commander/src/moveit_commander/move_group.py index a05c23cf85..0799e77c50 100644 --- a/moveit_commander/src/moveit_commander/move_group.py +++ b/moveit_commander/src/moveit_commander/move_group.py @@ -596,7 +596,7 @@ def retime_trajectory(self, ref_state_in, traj_in, velocity_scaling_factor=1.0, traj_out.deserialize(ser_traj_out) return traj_out - def get_jacobian_matrix(self, joint_values): + def get_jacobian_matrix(self, joint_values, reference_point=None): """ Get the jacobian matrix of the group as a list""" - return self._g.get_jacobian_matrix(joint_values) + return self._g.get_jacobian_matrix(joint_values, [0.0, 0.0, 0.0] if reference_point is None else reference_point) diff --git a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp index b3940182df..50646a8777 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp @@ -536,17 +536,28 @@ class MoveGroupInterfaceWrapper : protected py_bindings_tools::ROScppInitializer } } - Eigen::MatrixXd getJacobianMatrixPython(bp::list& joint_values) + Eigen::MatrixXd getJacobianMatrixPython(const bp::list& joint_values, + const bp::object& reference_point = bp::object()) { - std::vector v = py_bindings_tools::doubleFromList(joint_values); + const std::vector v = py_bindings_tools::doubleFromList(joint_values); + std::vector ref; + if (reference_point.is_none()) + ref = { 0.0, 0.0, 0.0 }; + else + ref = py_bindings_tools::doubleFromList(reference_point); + if (ref.size() != 3) + throw std::invalid_argument("reference point needs to have 3 elements, got " + std::to_string(ref.size())); + robot_state::RobotState state(getRobotModel()); state.setToDefaultValues(); auto group = state.getJointModelGroup(getName()); state.setJointGroupPositions(group, v); - return state.getJacobian(group); + return state.getJacobian(group, Eigen::Map(&ref[0])); } }; +BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(getJacobianMatrixOverloads, getJacobianMatrixPython, 1, 2) + static void wrap_move_group_interface() { eigenpy::enableEigenPy(); @@ -683,7 +694,8 @@ static void wrap_move_group_interface() move_group_interface_class.def("get_named_targets", &MoveGroupInterfaceWrapper::getNamedTargetsPython); move_group_interface_class.def("get_named_target_values", &MoveGroupInterfaceWrapper::getNamedTargetValuesPython); move_group_interface_class.def("get_current_state_bounded", &MoveGroupInterfaceWrapper::getCurrentStateBoundedPython); - move_group_interface_class.def("get_jacobian_matrix", &MoveGroupInterfaceWrapper::getJacobianMatrixPython); + move_group_interface_class.def("get_jacobian_matrix", &MoveGroupInterfaceWrapper::getJacobianMatrixPython, + getJacobianMatrixOverloads()); } } // namespace planning_interface } // namespace moveit diff --git a/moveit_ros/planning_interface/test/python_move_group.py b/moveit_ros/planning_interface/test/python_move_group.py index 4e388a6f16..0cc27cd09d 100755 --- a/moveit_ros/planning_interface/test/python_move_group.py +++ b/moveit_ros/planning_interface/test/python_move_group.py @@ -80,6 +80,13 @@ def test_get_jacobian_matrix(self): [ 1. , 0. , 0. , 0. , 0. , 0. ]]) self.assertTrue(np.allclose(result, expected)) + result = self.group.get_jacobian_matrix(current, [1.0, 1.0, 1.0]) + expected = np.array([[ 1. , 1.8 , -1.2 , 0. , -1. , 0. ], + [ 1.89, 0. , 0. , 1. , 0. , 1. ], + [ 0. , -1.74, 1.74, 1. , 1.1 , 1. ], + [ 0. , 0. , 0. , -1. , 0. , -1. ], + [ 0. , 1. , -1. , 0. , -1. , 0. ], + [ 1. , 0. , 0. , 0. , 0. , 0. ]]) if __name__ == '__main__': PKGNAME = 'moveit_ros_planning_interface' From 0957a61ac2943cbe6cba52c38e83d0b0fe9a09a8 Mon Sep 17 00:00:00 2001 From: v4hn Date: Thu, 15 Aug 2019 22:16:29 +0200 Subject: [PATCH 36/96] hide display state: sanity-check to allow for empty state input --- .../robot_state_rviz_plugin/src/robot_state_display.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index d843923605..d62f710a8c 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include @@ -303,7 +304,8 @@ void RobotStateDisplay::newRobotStateCallback(const moveit_msgs::DisplayRobotSta // possibly use TF to construct a robot_state::Transforms object to pass in to the conversion function? try { - robot_state::robotStateMsgToRobotState(state_msg->state, *robot_state_); + if (!planning_scene::PlanningScene::isEmpty(state_msg->state)) + robot_state::robotStateMsgToRobotState(state_msg->state, *robot_state_); setRobotHighlights(state_msg->highlight_links); setStatus(rviz::StatusProperty::Ok, "RobotState", ""); } From b0f01b2dc79f99f5650933834c8e50905bdbe168 Mon Sep 17 00:00:00 2001 From: v4hn Date: Thu, 15 Aug 2019 22:22:32 +0200 Subject: [PATCH 37/96] display robot state: do not clutter rviz with default robot on enable --- .../robot_state_rviz_plugin/src/robot_state_display.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index d62f710a8c..0b00428a90 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -375,7 +375,6 @@ void RobotStateDisplay::loadRobotModel() changedEnableVisualVisible(); changedEnableCollisionVisible(); - robot_->setVisible(true); } else setStatus(rviz::StatusProperty::Error, "RobotState", "No Planning Model Loaded"); From c5e88677654654f0f8aca9945bd1bd2205616958 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 17 Aug 2019 12:34:32 +0200 Subject: [PATCH 38/96] add status to warn if RobotState display is hidden --- .../src/robot_state_display.cpp | 17 +++++++++++++---- .../robot_state_visualization.h | 5 +++++ 2 files changed, 18 insertions(+), 4 deletions(-) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index 0b00428a90..70f2173d6a 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -290,6 +290,8 @@ void RobotStateDisplay::changedRobotStateTopic() if (static_cast(robot_state_)) robot_state_->setToDefaultValues(); update_state_ = true; + robot_->setVisible(false); + setStatus(rviz::StatusProperty::Warn, "RobotState", "No msg received"); robot_state_subscriber_ = root_nh_.subscribe(robot_state_topic_property_->getStdString(), 10, &RobotStateDisplay::newRobotStateCallback, this); @@ -307,17 +309,24 @@ void RobotStateDisplay::newRobotStateCallback(const moveit_msgs::DisplayRobotSta if (!planning_scene::PlanningScene::isEmpty(state_msg->state)) robot_state::robotStateMsgToRobotState(state_msg->state, *robot_state_); setRobotHighlights(state_msg->highlight_links); - setStatus(rviz::StatusProperty::Ok, "RobotState", ""); } catch (const moveit::Exception& e) { robot_state_->setToDefaultValues(); setRobotHighlights(moveit_msgs::DisplayRobotState::_highlight_links_type()); setStatus(rviz::StatusProperty::Error, "RobotState", e.what()); + robot_->setVisible(false); return; } - robot_->setVisible(!state_msg->hide); + if (robot_->isVisible() != !state_msg->hide) + { + robot_->setVisible(!state_msg->hide); + if (robot_->isVisible()) + setStatus(rviz::StatusProperty::Ok, "RobotState", ""); + else + setStatus(rviz::StatusProperty::Warn, "RobotState", "Hidden"); + } update_state_ = true; } @@ -371,13 +380,13 @@ void RobotStateDisplay::loadRobotModel() root_link_name_property_->setStdString(getRobotModel()->getRootLinkName()); root_link_name_property_->blockSignals(old_state); update_state_ = true; - setStatus(rviz::StatusProperty::Ok, "RobotState", "Planning Model Loaded Successfully"); + setStatus(rviz::StatusProperty::Ok, "RobotModel", "Loaded successfully"); changedEnableVisualVisible(); changedEnableCollisionVisible(); } else - setStatus(rviz::StatusProperty::Error, "RobotState", "No Planning Model Loaded"); + setStatus(rviz::StatusProperty::Error, "RobotModel", "Loading failed"); highlights_.clear(); } diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h index 49b299f1d1..09ffce9234 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h +++ b/moveit_ros/visualization/rviz_plugin_render_tools/include/moveit/rviz_plugin_render_tools/robot_state_visualization.h @@ -69,6 +69,11 @@ class RobotStateVisualization const std::map& color_map); void setDefaultAttachedObjectColor(const std_msgs::ColorRGBA& default_attached_object_color); + bool isVisible() const + { + return visible_; + } + /** * \brief Set the robot as a whole to be visible or not * @param visible Should we be visible? From 3854f7b58201c7590514828018e2ba1d70c60166 Mon Sep 17 00:00:00 2001 From: Raphael Druon Date: Sat, 17 Aug 2019 20:40:39 +0900 Subject: [PATCH 39/96] python planning_scene_interface: fix attaching objects (#1624) --- .../src/moveit_commander/planning_scene_interface.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/moveit_commander/src/moveit_commander/planning_scene_interface.py b/moveit_commander/src/moveit_commander/planning_scene_interface.py index a7fa6c9ad2..e0093e1508 100644 --- a/moveit_commander/src/moveit_commander/planning_scene_interface.py +++ b/moveit_commander/src/moveit_commander/planning_scene_interface.py @@ -69,7 +69,7 @@ def __init__(self, ns='', synchronous=False, service_timeout=5.0): def __submit(self, collision_object, attach=False): if self.__synchronous: - diff_req = self.__make_planning_scene_diff_req(collision_object) + diff_req = self.__make_planning_scene_diff_req(collision_object, attach) self._apply_planning_scene_diff.call(diff_req) else: if attach: @@ -306,10 +306,14 @@ def __make_cylinder(name, pose, height, radius): return co @staticmethod - def __make_planning_scene_diff_req(collision_object): + def __make_planning_scene_diff_req(collision_object, attach=False): scene = PlanningScene() scene.is_diff = True - scene.world.collision_objects = [collision_object] + scene.robot_state.is_diff = True + if attach: + scene.robot_state.attached_collision_objects = [collision_object] + else: + scene.world.collision_objects = [collision_object] planning_scene_diff_req = ApplyPlanningSceneRequest() planning_scene_diff_req.scene = scene return planning_scene_diff_req From 2e2552fef6b0a84b27db51a8c0bf319942019b4d Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Sat, 17 Aug 2019 15:33:34 +0200 Subject: [PATCH 40/96] Benchmark combinations of predefined poses (#1548) The CombinePredefinedPosesBenchmark allows conveniently planning trajectories between all pair-wise combinations of predefined poses that are specified in the benchmark config. --- moveit_ros/benchmarks/CMakeLists.txt | 4 + .../demo_panda_predefined_poses.launch | 33 ++++ .../examples/demo_panda_predefined_poses.yaml | 34 ++++ .../moveit/benchmarks/BenchmarkOptions.h | 28 ++++ .../benchmarks/src/BenchmarkExecutor.cpp | 2 + .../benchmarks/src/BenchmarkOptions.cpp | 12 ++ .../CombinePredefinedPosesBenchmark.cpp | 148 ++++++++++++++++++ 7 files changed, 261 insertions(+) create mode 100644 moveit_ros/benchmarks/examples/demo_panda_predefined_poses.launch create mode 100644 moveit_ros/benchmarks/examples/demo_panda_predefined_poses.yaml create mode 100644 moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index 2463628a58..8a8f447e19 100644 --- a/moveit_ros/benchmarks/CMakeLists.txt +++ b/moveit_ros/benchmarks/CMakeLists.txt @@ -40,10 +40,14 @@ target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) add_executable(moveit_run_benchmark src/RunBenchmark.cpp) target_link_libraries(moveit_run_benchmark ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) +add_executable(moveit_combine_predefined_poses_benchmark src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp) +target_link_libraries(moveit_combine_predefined_poses_benchmark ${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) install( TARGETS ${MOVEIT_LIB_NAME} + moveit_run_benchmark + moveit_combine_predefined_poses_benchmark LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}) diff --git a/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.launch b/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.launch new file mode 100644 index 0000000000..657fad0a6f --- /dev/null +++ b/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.yaml b/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.yaml new file mode 100644 index 0000000000..94f7803595 --- /dev/null +++ b/moveit_ros/benchmarks/examples/demo_panda_predefined_poses.yaml @@ -0,0 +1,34 @@ +# This is an example configuration that loads the "Kitchen" scene from the +# local MoveIt warehouse and benchmarks the "manipulator" group over all pairs +# of motion plan queries and start states in the Kitchen scene. + +# Five planners from two different plugins are run a total of 50 times each, with a +# maximum of 10 seconds per run. Output is stored in the /tmp/moveit_benchmarks directory. + +benchmark_config: + warehouse: + host: 127.0.0.1 + port: 33829 + scene_name: Kitchen # Required + parameters: + name: KitchenPick1 + runs: 50 + group: panda_arm # Required + timeout: 10.0 + output_directory: /tmp/moveit_benchmarks/ + predefined_poses_group: panda_arm_hand # Group where the predefined poses are specified + predefined_poses: # List of named targets + - ready + - extended + planning_pipelines: + - name: ompl + planners: + - RRTConnectkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - name: chomp + planners: + - CHOMP + - name: stomp + planners: + - STOMP diff --git a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h index 0006d42f39..92c7671529 100644 --- a/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h +++ b/moveit_ros/benchmarks/include/moveit/benchmarks/BenchmarkOptions.h @@ -47,31 +47,57 @@ namespace moveit_ros_benchmarks class BenchmarkOptions { public: + /** \brief Constructor */ BenchmarkOptions(); + /** \brief Constructor accepting a custom namespace for parameter lookup */ BenchmarkOptions(const std::string& ros_namespace); + /** \brief Destructor */ virtual ~BenchmarkOptions(); + /** \brief Set the ROS namespace the node handle should use for parameter lookup */ void setNamespace(const std::string& ros_namespace); + /** \brief Get the name of the warehouse database host server */ const std::string& getHostName() const; + /** \brief Get the port of the warehouse database host server */ int getPort() const; + /** \brief Get the reference name of the planning scene stored inside the warehouse database */ const std::string& getSceneName() const; + /** \brief Get the specified number of benchmark query runs */ int getNumRuns() const; + /** \brief Get the maximum timeout per planning attempt */ double getTimeout() const; + /** \brief Get the reference name of the benchmark */ const std::string& getBenchmarkName() const; + /** \brief Get the name of the planning group to run the benchmark with */ const std::string& getGroupName() const; + /** \brief Get the target directory for the generated benchmark result data */ const std::string& getOutputDirectory() const; + /** \brief Get the regex expression for matching the names of all queries to run */ const std::string& getQueryRegex() const; + /** \brief Get the regex expression for matching the names of all start states to plan from */ const std::string& getStartStateRegex() const; + /** \brief Get the regex expression for matching the names of all goal constraints to plan to */ const std::string& getGoalConstraintRegex() const; + /** \brief Get the regex expression for matching the names of all path constraints to plan with */ const std::string& getPathConstraintRegex() const; + /** \brief Get the regex expression for matching the names of all trajectory constraints to plan with */ const std::string& getTrajectoryConstraintRegex() const; + /** \brief Get the names of all predefined poses to consider for planning */ + const std::vector& getPredefinedPoses() const; + /** \brief Get the name of the planning group for which the predefined poses are defined */ + const std::string& getPredefinedPosesGroup() const; + /** \brief Get the constant position/orientation offset to be used for shifting all goal constraints */ void getGoalOffsets(std::vector& offsets) const; + /** \brief Get all planning pipeline names mapped to their parameter configuration */ const std::map>& getPlanningPipelineConfigurations() const; + /** \brief Get all planning pipeline names */ void getPlanningPipelineNames(std::vector& planning_pipeline_names) const; + /* \brief Get the frame id of the planning workspace */ const std::string& getWorkspaceFrameID() const; + /* \brief Get the parameter set of the planning workspace */ const moveit_msgs::WorkspaceParameters& getWorkspaceParameters() const; protected: @@ -100,6 +126,8 @@ class BenchmarkOptions std::string goal_constraint_regex_; std::string path_constraint_regex_; std::string trajectory_constraint_regex_; + std::vector predefined_poses_; + std::string predefined_poses_group_; double goal_offsets[6]; /// planner configurations diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 4f717cd97a..8e15bad1c1 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -501,6 +501,8 @@ bool BenchmarkExecutor::plannerConfigurationsExist( for (const std::pair& pipeline_entry : planning_pipelines_) { pipeline_exists = pipeline_entry.first == pipeline_config_entry.first; + if (pipeline_exists) + break; } if (!pipeline_exists) diff --git a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp index 1ed9c512a1..96dd820afb 100644 --- a/moveit_ros/benchmarks/src/BenchmarkOptions.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkOptions.cpp @@ -136,6 +136,16 @@ const std::string& BenchmarkOptions::getTrajectoryConstraintRegex() const return trajectory_constraint_regex_; } +const std::vector& BenchmarkOptions::getPredefinedPoses() const +{ + return predefined_poses_; +} + +const std::string& BenchmarkOptions::getPredefinedPosesGroup() const +{ + return predefined_poses_group_; +} + void BenchmarkOptions::getGoalOffsets(std::vector& offsets) const { offsets.resize(6); @@ -189,6 +199,8 @@ void BenchmarkOptions::readBenchmarkParameters(ros::NodeHandle& nh) nh.param(std::string("benchmark_config/parameters/path_constraints"), path_constraint_regex_, std::string("")); nh.param(std::string("benchmark_config/parameters/trajectory_constraints"), trajectory_constraint_regex_, std::string("")); + nh.param(std::string("benchmark_config/parameters/predefined_poses"), predefined_poses_, {}); + nh.param(std::string("benchmark_config/parameters/predefined_poses_group"), predefined_poses_group_, std::string("")); if (!nh.getParam(std::string("benchmark_config/parameters/group"), group_name_)) ROS_WARN("Benchmark group NOT specified"); diff --git a/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp new file mode 100644 index 0000000000..5c6bdd4c51 --- /dev/null +++ b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp @@ -0,0 +1,148 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2019, PickNik LLC +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the PickNik LLC nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +/* Author: Henning Kayser */ +/* Description: A simple benchmark that plans trajectories for all combinations of specified predefined poses */ + +// MoveIt Benchmark +#include +#include + +// MoveIt +#include +#include +#include + +namespace moveit_ros_benchmarks +{ +constexpr char LOGNAME[] = "combine_predefined_poses_benchmark"; +class CombinePredefinedPosesBenchmark : public BenchmarkExecutor +{ +public: + virtual bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, + std::vector& start_states, + std::vector& path_constraints, + std::vector& goal_constraints, + std::vector& traj_constraints, + std::vector& queries) + { + // Load planning scene + if (!psm_) + psm_.reset(new planning_scene_monitor::PlanningSceneMonitor("robot_description")); + if (!psm_->newPlanningSceneMessage(scene_msg)) + { + ROS_ERROR_NAMED(LOGNAME, "Failed to load planning scene"); + return false; + } + + // Load robot model + if (!psm_->getRobotModel()) + { + ROS_ERROR_NAMED(LOGNAME, "Failed to load robot model"); + return false; + } + + // Select planning group to use for predefined poses + std::string predefined_poses_group = opts.getPredefinedPosesGroup(); + if (predefined_poses_group.empty()) + { + ROS_WARN_NAMED(LOGNAME, "Parameter predefined_poses_group is not set, using default planning group instead"); + predefined_poses_group = opts.getGroupName(); + } + const auto& joint_model_group = psm_->getRobotModel()->getJointModelGroup(predefined_poses_group); + if (!joint_model_group) + { + ROS_ERROR_STREAM_NAMED(LOGNAME, "Robot model has no joint model group named '" << predefined_poses_group << "'"); + return false; + } + + // Iterate over all predefined poses and use each as start and goal states + moveit::core::RobotState robot_state(psm_->getRobotModel()); + start_states.clear(); + goal_constraints.clear(); + for (const auto& pose_id : opts.getPredefinedPoses()) + { + if (!robot_state.setToDefaultValues(joint_model_group, pose_id)) + { + ROS_WARN_STREAM_NAMED(LOGNAME, "Failed to set robot state to named target '" << pose_id << "'"); + continue; + } + // Create start state + start_states.emplace_back(); + start_states.back().name = pose_id; + moveit::core::robotStateToRobotStateMsg(robot_state, start_states.back().state); + + // Create goal constraints + goal_constraints.emplace_back(); + goal_constraints.back().name = pose_id; + goal_constraints.back().constraints.push_back( + kinematic_constraints::constructGoalConstraints(robot_state, joint_model_group)); + } + if (start_states.empty() || goal_constraints.empty()) + { + ROS_ERROR_NAMED(LOGNAME, "Failed to init start and goal states from predefined_poses"); + return false; + } + + // We don't use path/trajectory constraints or custom queries + path_constraints.clear(); + traj_constraints.clear(); + queries.clear(); + return true; + } + +private: + planning_scene_monitor::PlanningSceneMonitorPtr psm_; +}; +} // namespace moveit_ros_benchmarks + +int main(int argc, char** argv) +{ + ros::init(argc, argv, "moveit_run_benchmark"); + ros::AsyncSpinner spinner(1); + spinner.start(); + + // Read benchmark options from param server + moveit_ros_benchmarks::BenchmarkOptions opts(ros::this_node::getName()); + // Setup benchmark server + moveit_ros_benchmarks::CombinePredefinedPosesBenchmark server; + + std::vector planning_pipelines; + opts.getPlanningPipelineNames(planning_pipelines); + server.initialize(planning_pipelines); + + // Running benchmarks + if (!server.runBenchmarks(opts)) + ROS_ERROR("Failed to run all benchmarks"); +} From e7bc01e9d5557f0ad63724be65197d1bde15333c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Sat, 17 Aug 2019 17:18:58 +0200 Subject: [PATCH 41/96] PlanningRequestAdapter::initialize() = 0 (#1621) Implement initialize as pure virtual function. --- .../planning_request_adapter.h | 25 +++---------------- 1 file changed, 3 insertions(+), 22 deletions(-) diff --git a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h index 9c11302a02..daf9426ba0 100644 --- a/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h +++ b/moveit_core/planning_request_adapter/include/moveit/planning_request_adapter/planning_request_adapter.h @@ -40,9 +40,6 @@ #include #include #include -#if !defined(_MSC_VER) -#include -#endif /** \brief Generic interface to adapting motion planning requests */ namespace planning_request_adapter @@ -65,25 +62,9 @@ class PlanningRequestAdapter { } - /// Initialize parameters using the passed NodeHandle - // TODO - Make initialize() a pure virtual function in O-turtle - virtual void initialize(const ros::NodeHandle& node_handle) - { - // Get name of derived adapter - std::string adapter_name = typeid(*this).name(); - // Try to demangle the name - int status = 1; -#if defined(_MSC_VER) - std::string demangled_name = adapter_name; -#else - std::string demangled_name = abi::__cxa_demangle(adapter_name.c_str(), NULL, NULL, &status); -#endif - if (status == 0) - adapter_name = demangled_name; - ROS_WARN_NAMED("planning_request_adapter", "Implementation of function initialize() is missing from '%s'." - "Any parameters should be loaded from the passed NodeHandle.", - adapter_name.c_str()); - } + /** \brief Initialize parameters using the passed NodeHandle + if no initialization is needed, simply implement as empty */ + virtual void initialize(const ros::NodeHandle& node_handle) = 0; /// Get a short string that identifies the planning request adapter virtual std::string getDescription() const From 4ca54cd0cda1bc0ceef072d769357ce3802e62da Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Mon, 19 Aug 2019 11:23:58 +0200 Subject: [PATCH 42/96] move isEmpty test functions to moveit_core/utils (#1627) --- .../moveit/kinematic_constraints/utils.h | 2 +- .../kinematic_constraints/src/utils.cpp | 4 +- .../moveit/planning_scene/planning_scene.h | 8 +- .../planning_scene/src/planning_scene.cpp | 15 +--- .../test/test_planning_scene.cpp | 5 +- moveit_core/utils/CMakeLists.txt | 1 + .../include/moveit/utils/message_checks.h | 65 +++++++++++++++++ moveit_core/utils/src/message_checks.cpp | 73 +++++++++++++++++++ .../src/generate_state_database.cpp | 3 +- .../manipulation/pick_place/src/pick.cpp | 3 +- .../manipulation/pick_place/src/place.cpp | 3 +- .../cartesian_path_service_capability.cpp | 4 +- .../kinematics_service_capability.cpp | 4 +- .../move_action_capability.cpp | 10 +-- .../state_validation_service_capability.cpp | 4 +- .../plan_execution/src/plan_execution.cpp | 3 +- .../src/planning_scene_monitor.cpp | 5 +- .../src/robot_state_display.cpp | 4 +- 18 files changed, 178 insertions(+), 38 deletions(-) create mode 100644 moveit_core/utils/include/moveit/utils/message_checks.h create mode 100644 moveit_core/utils/src/message_checks.cpp diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h index f2dfe6f84a..54080fbacb 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h @@ -67,7 +67,7 @@ moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints& first, const moveit_msgs::Constraints& second); /** \brief Check if any constraints were specified */ -bool isEmpty(const moveit_msgs::Constraints& constr); +[[deprecated("Use moveit/utils/message_checks.h instead")]] bool isEmpty(const moveit_msgs::Constraints& constr); std::size_t countIndividualConstraints(const moveit_msgs::Constraints& constr); diff --git a/moveit_core/kinematic_constraints/src/utils.cpp b/moveit_core/kinematic_constraints/src/utils.cpp index 568efbb95b..59beecec6c 100644 --- a/moveit_core/kinematic_constraints/src/utils.cpp +++ b/moveit_core/kinematic_constraints/src/utils.cpp @@ -38,6 +38,7 @@ #include #include #include +#include using namespace moveit::core; @@ -116,8 +117,7 @@ moveit_msgs::Constraints mergeConstraints(const moveit_msgs::Constraints& first, bool isEmpty(const moveit_msgs::Constraints& constr) { - return constr.position_constraints.empty() && constr.orientation_constraints.empty() && - constr.visibility_constraints.empty() && constr.joint_constraints.empty(); + return moveit::core::isEmpty(constr); } std::size_t countIndividualConstraints(const moveit_msgs::Constraints& constr) diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index 32adb11f61..c7954cce12 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -953,14 +953,16 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from /** \brief Check if a message includes any information about a planning scene, or it is just a default, empty message. */ - static bool isEmpty(const moveit_msgs::PlanningScene& msg); + [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool + isEmpty(const moveit_msgs::PlanningScene& msg); /** \brief Check if a message includes any information about a planning scene world, or it is just a default, empty * message. */ - static bool isEmpty(const moveit_msgs::PlanningSceneWorld& msg); + [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool + isEmpty(const moveit_msgs::PlanningSceneWorld& msg); /** \brief Check if a message includes any information about a robot state, or it is just a default, empty message. */ - static bool isEmpty(const moveit_msgs::RobotState& msg); + [[deprecated("Use moveit/utils/message_checks.h instead")]] static bool isEmpty(const moveit_msgs::RobotState& msg); /** \brief Clone a planning scene. Even if the scene \e scene depends on a parent, the cloned scene will not. */ static PlanningScenePtr clone(const PlanningSceneConstPtr& scene); diff --git a/moveit_core/planning_scene/src/planning_scene.cpp b/moveit_core/planning_scene/src/planning_scene.cpp index 37b62f4d85..279f824e83 100644 --- a/moveit_core/planning_scene/src/planning_scene.cpp +++ b/moveit_core/planning_scene/src/planning_scene.cpp @@ -43,6 +43,7 @@ #include #include #include +#include #include #include #include @@ -96,25 +97,17 @@ class SceneTransforms : public robot_state::Transforms bool PlanningScene::isEmpty(const moveit_msgs::PlanningScene& msg) { - return msg.name.empty() && msg.fixed_frame_transforms.empty() && msg.allowed_collision_matrix.entry_names.empty() && - msg.link_padding.empty() && msg.link_scale.empty() && isEmpty(msg.robot_state) && isEmpty(msg.world); + return moveit::core::isEmpty(msg); } bool PlanningScene::isEmpty(const moveit_msgs::RobotState& msg) { - /* a state is empty if it includes no information and it is a diff; if the state is not a diff, then the implicit - information is - that the set of attached bodies is empty, so they must be cleared from the state to be updated */ - return static_cast(msg.is_diff) && msg.multi_dof_joint_state.joint_names.empty() && - msg.joint_state.name.empty() && msg.attached_collision_objects.empty() && msg.joint_state.position.empty() && - msg.joint_state.velocity.empty() && msg.joint_state.effort.empty() && - msg.multi_dof_joint_state.transforms.empty() && msg.multi_dof_joint_state.twist.empty() && - msg.multi_dof_joint_state.wrench.empty(); + return moveit::core::isEmpty(msg); } bool PlanningScene::isEmpty(const moveit_msgs::PlanningSceneWorld& msg) { - return msg.collision_objects.empty() && msg.octomap.octomap.data.empty(); + return moveit::core::isEmpty(msg); } PlanningScene::PlanningScene(const robot_model::RobotModelConstPtr& robot_model, diff --git a/moveit_core/planning_scene/test/test_planning_scene.cpp b/moveit_core/planning_scene/test/test_planning_scene.cpp index 73b68186e3..9d93148edb 100644 --- a/moveit_core/planning_scene/test/test_planning_scene.cpp +++ b/moveit_core/planning_scene/test/test_planning_scene.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include #include @@ -104,10 +105,10 @@ TEST(PlanningScene, LoadRestoreDiff) moveit_msgs::PlanningScene ps_msg; ps_msg.robot_state.is_diff = true; - EXPECT_TRUE(planning_scene::PlanningScene::isEmpty(ps_msg)); + EXPECT_TRUE(moveit::core::isEmpty(ps_msg)); ps->getPlanningSceneMsg(ps_msg); ps->setPlanningSceneMsg(ps_msg); - EXPECT_FALSE(planning_scene::PlanningScene::isEmpty(ps_msg)); + EXPECT_FALSE(moveit::core::isEmpty(ps_msg)); EXPECT_TRUE(world.hasObject("sphere")); planning_scene::PlanningScenePtr next = ps->diff(); diff --git a/moveit_core/utils/CMakeLists.txt b/moveit_core/utils/CMakeLists.txt index 9ea399702a..8a9aaa49bd 100644 --- a/moveit_core/utils/CMakeLists.txt +++ b/moveit_core/utils/CMakeLists.txt @@ -3,6 +3,7 @@ set(MOVEIT_LIB_NAME moveit_utils) add_library(${MOVEIT_LIB_NAME} src/lexical_casts.cpp src/xmlrpc_casts.cpp + src/message_checks.cpp ) target_link_libraries(${MOVEIT_LIB_NAME} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) diff --git a/moveit_core/utils/include/moveit/utils/message_checks.h b/moveit_core/utils/include/moveit/utils/message_checks.h new file mode 100644 index 0000000000..4ac3c0af8d --- /dev/null +++ b/moveit_core/utils/include/moveit/utils/message_checks.h @@ -0,0 +1,65 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Universitaet Hamburg. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Michael 'v4hn' Goerner */ + +#pragma once + +/** \file empty_msgs.h + * \brief Checks for empty MoveIt-related messages + * + */ + +#include +#include +#include +#include + +namespace moveit +{ +namespace core +{ +/** \brief Check if a message includes any information about a planning scene, or whether it is empty. */ +bool isEmpty(const moveit_msgs::PlanningScene& msg); + +/** \brief Check if a message includes any information about a planning scene world, or whether it is empty. */ +bool isEmpty(const moveit_msgs::PlanningSceneWorld& msg); + +/** \brief Check if a message includes any information about a robot state, or whether it is empty. */ +bool isEmpty(const moveit_msgs::RobotState& msg); + +/** \brief Check if a message specifies constraints */ +bool isEmpty(const moveit_msgs::Constraints& msg); +} +} diff --git a/moveit_core/utils/src/message_checks.cpp b/moveit_core/utils/src/message_checks.cpp new file mode 100644 index 0000000000..b466e4768b --- /dev/null +++ b/moveit_core/utils/src/message_checks.cpp @@ -0,0 +1,73 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Universitaet Hamburg. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Hamburg University nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Michael Goerner */ + +#include + +namespace moveit +{ +namespace core +{ +bool isEmpty(const moveit_msgs::PlanningScene& msg) +{ + return msg.name.empty() && msg.fixed_frame_transforms.empty() && msg.allowed_collision_matrix.entry_names.empty() && + msg.link_padding.empty() && msg.link_scale.empty() && isEmpty(msg.robot_state) && isEmpty(msg.world); +} + +bool isEmpty(const moveit_msgs::PlanningSceneWorld& msg) +{ + return msg.collision_objects.empty() && msg.octomap.octomap.data.empty(); +} + +bool isEmpty(const moveit_msgs::RobotState& msg) +{ + /* a state is empty if it includes no information and it is a diff; if the state is not a diff, then the implicit + information is + that the set of attached bodies is empty, so they must be cleared from the state to be updated */ + return static_cast(msg.is_diff) && msg.multi_dof_joint_state.joint_names.empty() && + msg.joint_state.name.empty() && msg.attached_collision_objects.empty() && msg.joint_state.position.empty() && + msg.joint_state.velocity.empty() && msg.joint_state.effort.empty() && + msg.multi_dof_joint_state.transforms.empty() && msg.multi_dof_joint_state.twist.empty() && + msg.multi_dof_joint_state.wrench.empty(); +} + +bool isEmpty(const moveit_msgs::Constraints& constr) +{ + return constr.position_constraints.empty() && constr.orientation_constraints.empty() && + constr.visibility_constraints.empty() && constr.joint_constraints.empty(); +} + +} // namespace core +} // namespace moveit diff --git a/moveit_planners/ompl/ompl_interface/src/generate_state_database.cpp b/moveit_planners/ompl/ompl_interface/src/generate_state_database.cpp index f1cd7d56c6..e2cbf39c25 100644 --- a/moveit_planners/ompl/ompl_interface/src/generate_state_database.cpp +++ b/moveit_planners/ompl/ompl_interface/src/generate_state_database.cpp @@ -42,6 +42,7 @@ #include #include +#include #include #include @@ -165,7 +166,7 @@ int main(int argc, char** argv) } } - if (kinematic_constraints::isEmpty(params.constraints)) + if (moveit::core::isEmpty(params.constraints)) { ROS_FATAL_NAMED(LOGNAME, "Abort. Constraint description is an empty set of constraints."); return 1; diff --git a/moveit_ros/manipulation/pick_place/src/pick.cpp b/moveit_ros/manipulation/pick_place/src/pick.cpp index 5b922a6589..f2e868ae79 100644 --- a/moveit_ros/manipulation/pick_place/src/pick.cpp +++ b/moveit_ros/manipulation/pick_place/src/pick.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include namespace pick_place @@ -230,7 +231,7 @@ PickPlanPtr PickPlace::planPick(const planning_scene::PlanningSceneConstPtr& pla { PickPlanPtr p(new PickPlan(shared_from_this())); - if (planning_scene::PlanningScene::isEmpty(goal.planning_options.planning_scene_diff)) + if (moveit::core::isEmpty(goal.planning_options.planning_scene_diff)) p->plan(planning_scene, goal); else p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal); diff --git a/moveit_ros/manipulation/pick_place/src/place.cpp b/moveit_ros/manipulation/pick_place/src/place.cpp index 098d5c1438..ae7e1f04cf 100644 --- a/moveit_ros/manipulation/pick_place/src/place.cpp +++ b/moveit_ros/manipulation/pick_place/src/place.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #include #include @@ -369,7 +370,7 @@ PlacePlanPtr PickPlace::planPlace(const planning_scene::PlanningSceneConstPtr& p const moveit_msgs::PlaceGoal& goal) const { PlacePlanPtr p(new PlacePlan(shared_from_this())); - if (planning_scene::PlanningScene::isEmpty(goal.planning_options.planning_scene_diff)) + if (moveit::core::isEmpty(goal.planning_options.planning_scene_diff)) p->plan(planning_scene, goal); else p->plan(planning_scene->diff(goal.planning_options.planning_scene_diff), goal); diff --git a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp index 15d5d29c60..a2f467b1d9 100644 --- a/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/cartesian_path_service_capability.cpp @@ -36,7 +36,7 @@ #include "cartesian_path_service_capability.h" #include -#include +#include #include #include #include @@ -131,7 +131,7 @@ bool MoveGroupCartesianPathService::computeService(moveit_msgs::GetCartesianPath robot_state::GroupStateValidityCallbackFn constraint_fn; std::unique_ptr ls; std::unique_ptr kset; - if (req.avoid_collisions || !kinematic_constraints::isEmpty(req.path_constraints)) + if (req.avoid_collisions || !moveit::core::isEmpty(req.path_constraints)) { ls.reset(new planning_scene_monitor::LockedPlanningSceneRO(context_->planning_scene_monitor_)); kset.reset(new kinematic_constraints::KinematicConstraintSet((*ls)->getRobotModel())); diff --git a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp index 73e3932e18..b1e86fa6b4 100644 --- a/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/kinematics_service_capability.cpp @@ -36,7 +36,7 @@ #include "kinematics_service_capability.h" #include -#include +#include #include #include @@ -148,7 +148,7 @@ bool MoveGroupKinematicsService::computeIKService(moveit_msgs::GetPositionIK::Re context_->planning_scene_monitor_->updateFrameTransforms(); // check if the planning scene needs to be kept locked; if so, call computeIK() in the scope of the lock - if (req.ik_request.avoid_collisions || !kinematic_constraints::isEmpty(req.ik_request.constraints)) + if (req.ik_request.avoid_collisions || !moveit::core::isEmpty(req.ik_request.constraints)) { planning_scene_monitor::LockedPlanningSceneRO ls(context_->planning_scene_monitor_); kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel()); diff --git a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp index cc6c36557a..26c619b7d8 100644 --- a/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/move_action_capability.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include namespace move_group @@ -102,7 +103,7 @@ void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const moveit_msgs::M ROS_INFO_NAMED(getName(), "Combined planning and execution request received for MoveGroup action. " "Forwarding to planning and execution pipeline."); - if (planning_scene::PlanningScene::isEmpty(goal->planning_options.planning_scene_diff)) + if (moveit::core::isEmpty(goal->planning_options.planning_scene_diff)) { planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_); const robot_state::RobotState& current_state = lscene->getCurrentState(); @@ -122,10 +123,9 @@ void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const moveit_msgs::M plan_execution::PlanExecution::Options opt; const moveit_msgs::MotionPlanRequest& motion_plan_request = - planning_scene::PlanningScene::isEmpty(goal->request.start_state) ? goal->request : - clearRequestStartState(goal->request); + moveit::core::isEmpty(goal->request.start_state) ? goal->request : clearRequestStartState(goal->request); const moveit_msgs::PlanningScene& planning_scene_diff = - planning_scene::PlanningScene::isEmpty(goal->planning_options.planning_scene_diff.robot_state) ? + moveit::core::isEmpty(goal->planning_options.planning_scene_diff.robot_state) ? goal->planning_options.planning_scene_diff : clearSceneRobotState(goal->planning_options.planning_scene_diff); @@ -168,7 +168,7 @@ void MoveGroupMoveAction::executeMoveCallbackPlanOnly(const moveit_msgs::MoveGro // lock the scene so that it does not modify the world representation while diff() is called planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_); const planning_scene::PlanningSceneConstPtr& the_scene = - (planning_scene::PlanningScene::isEmpty(goal->planning_options.planning_scene_diff)) ? + (moveit::core::isEmpty(goal->planning_options.planning_scene_diff)) ? static_cast(lscene) : lscene->diff(goal->planning_options.planning_scene_diff); planning_interface::MotionPlanResponse res; diff --git a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp index 16e6714665..c333f4a9a7 100644 --- a/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp +++ b/moveit_ros/move_group/src/default_capabilities/state_validation_service_capability.cpp @@ -36,7 +36,7 @@ #include "state_validation_service_capability.h" #include -#include +#include #include #include @@ -100,7 +100,7 @@ bool MoveGroupStateValidationService::computeService(moveit_msgs::GetStateValidi } // evaluate constraints - if (!kinematic_constraints::isEmpty(req.constraints)) + if (!moveit::core::isEmpty(req.constraints)) { kinematic_constraints::KinematicConstraintSet kset(ls->getRobotModel()); kset.add(req.constraints, ls->getTransforms()); diff --git a/moveit_ros/planning/plan_execution/src/plan_execution.cpp b/moveit_ros/planning/plan_execution/src/plan_execution.cpp index 6621592343..e3f9bb84a9 100644 --- a/moveit_ros/planning/plan_execution/src/plan_execution.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_execution.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include @@ -141,7 +142,7 @@ void plan_execution::PlanExecution::planAndExecute(ExecutableMotionPlan& plan, c void plan_execution::PlanExecution::planAndExecute(ExecutableMotionPlan& plan, const moveit_msgs::PlanningScene& scene_diff, const Options& opt) { - if (planning_scene::PlanningScene::isEmpty(scene_diff)) + if (moveit::core::isEmpty(scene_diff)) planAndExecute(plan, opt); else { diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index 23a0ca3f28..a2138f668d 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -36,6 +36,7 @@ #include #include +#include #include #include @@ -565,13 +566,13 @@ bool PlanningSceneMonitor::newPlanningSceneMessage(const moveit_msgs::PlanningSc if (no_other_scene_upd) { upd = UPDATE_NONE; - if (!planning_scene::PlanningScene::isEmpty(scene.world)) + if (!moveit::core::isEmpty(scene.world)) upd = (SceneUpdateType)((int)upd | (int)UPDATE_GEOMETRY); if (!scene.fixed_frame_transforms.empty()) upd = (SceneUpdateType)((int)upd | (int)UPDATE_TRANSFORMS); - if (!planning_scene::PlanningScene::isEmpty(scene.robot_state)) + if (!moveit::core::isEmpty(scene.robot_state)) { upd = (SceneUpdateType)((int)upd | (int)UPDATE_STATE); if (!scene.robot_state.attached_collision_objects.empty() || !static_cast(scene.robot_state.is_diff)) diff --git a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp index 70f2173d6a..98e024fea0 100644 --- a/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp +++ b/moveit_ros/visualization/robot_state_rviz_plugin/src/robot_state_display.cpp @@ -36,7 +36,7 @@ #include #include -#include +#include #include #include @@ -306,7 +306,7 @@ void RobotStateDisplay::newRobotStateCallback(const moveit_msgs::DisplayRobotSta // possibly use TF to construct a robot_state::Transforms object to pass in to the conversion function? try { - if (!planning_scene::PlanningScene::isEmpty(state_msg->state)) + if (!moveit::core::isEmpty(state_msg->state)) robot_state::robotStateMsgToRobotState(state_msg->state, *robot_state_); setRobotHighlights(state_msg->highlight_links); } From 1f4de10e72e2a414a6df421df396a84677e8af5f Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Wed, 21 Aug 2019 04:35:47 -0700 Subject: [PATCH 43/96] favor ros::Duration.sleep over sleep. (#1634) --- .../planning_components_tools/src/display_random_state.cpp | 2 +- .../planning_components_tools/src/publish_scene_from_text.cpp | 2 +- .../planning/planning_scene_monitor/demos/demo_scene.cpp | 2 +- .../planning_interface/move_group_interface/src/demo.cpp | 2 +- moveit_setup_assistant/src/widgets/start_screen_widget.cpp | 4 ++-- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp b/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp index f70c4e0860..ac7bf2c7ec 100644 --- a/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp +++ b/moveit_ros/planning/planning_components_tools/src/display_random_state.cpp @@ -136,7 +136,7 @@ int main(int argc, char** argv) pub_scene.publish(psmsg); std::cout << psm.getPlanningScene()->getCurrentState() << std::endl; - sleep(1); + ros::Duration(1).sleep(); } } while (nh.ok()); diff --git a/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp b/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp index 274e250433..b2f441d5c8 100644 --- a/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp +++ b/moveit_ros/planning/planning_components_tools/src/publish_scene_from_text.cpp @@ -90,7 +90,7 @@ int main(int argc, char** argv) else pub_scene.publish(ps_msg.world); - sleep(1); + ros::Duration(1).sleep(); } } else diff --git a/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp b/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp index 681d6af0d2..976f1ba678 100644 --- a/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp +++ b/moveit_ros/planning/planning_scene_monitor/demos/demo_scene.cpp @@ -76,7 +76,7 @@ void sendKnife() co.primitive_poses[0].orientation.w = 1.0; pub_aco.publish(aco); - sleep(1); + ros::Duration(1).sleep(); pub_aco.publish(aco); ROS_INFO("Object published."); ros::Duration(1.5).sleep(); diff --git a/moveit_ros/planning_interface/move_group_interface/src/demo.cpp b/moveit_ros/planning_interface/move_group_interface/src/demo.cpp index 6aba08bcc6..0bd7017fce 100644 --- a/moveit_ros/planning_interface/move_group_interface/src/demo.cpp +++ b/moveit_ros/planning_interface/move_group_interface/src/demo.cpp @@ -115,7 +115,7 @@ int main(int argc, char** argv) moveit::planning_interface::MoveGroupInterface group(argc > 1 ? argv[1] : "right_arm"); demoPlace(group); - sleep(2); + ros::Duration(2).sleep(); return 0; } diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index 10320c3b1f..a980d61071 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -561,7 +561,7 @@ bool StartScreenWidget::loadURDFFile(const std::string& urdf_file_path, const st while (!nh.ok() && steps < 4) { ROS_WARN("Waiting for node handle"); - sleep(1); + ros::Duration(1).sleep(); steps++; ros::spinOnce(); } @@ -610,7 +610,7 @@ bool StartScreenWidget::setSRDFFile(const std::string& srdf_string) while (!nh.ok() && steps < 4) { ROS_WARN("Waiting for node handle"); - sleep(1); + ros::Duration(1).sleep(); steps++; ros::spinOnce(); } From 8066a509ddb3a4c61ca2ebe2add8f0e2997e95d0 Mon Sep 17 00:00:00 2001 From: Jens P Date: Wed, 21 Aug 2019 17:13:13 +0200 Subject: [PATCH 44/96] Unified Collision Environment Integration (#1584) * Unified collision environment * Integrating FCL unified environment into the planning scene * Distance field collision environment * Collision distance field and hybrid compiles * PR review: * collision environmnet test cases adapted * allocating of child planning scenes * valided padding and scaling added * reordering of member variables and functions * license adaptions * Unified all_valid collision detector * Replace references to CollisionWorld / CollisionRobot to new CollisionEnv * SBPL planner adapted for unified collision environment * PR review: * added as author * added documentation to collision environments * Added change description to migration notes. * Replaced getCollisionWorld/Robot with getCollisionEnv functions * PR review: * change to pragma once include guards * enable test --- MIGRATION.md | 1 + .../collision_detection/CMakeLists.txt | 6 +- .../collision_detector_allocator_allvalid.h | 8 +- ...ld_allvalid.h => collision_env_allvalid.h} | 54 +- .../allvalid/collision_robot_allvalid.h | 85 --- .../collision_detector_allocator.h | 34 +- .../{collision_robot.h => collision_env.h} | 231 +++---- .../collision_octomap_filter.h | 2 +- .../collision_detection/collision_plugin.h | 6 +- .../collision_detection/collision_world.h | 279 -------- ...llvalid.cpp => collision_env_allvalid.cpp} | 100 ++- .../src/allvalid/collision_robot_allvalid.cpp | 171 ----- ...{collision_robot.cpp => collision_env.cpp} | 91 ++- .../src/collision_octomap_filter.cpp | 1 - .../src/collision_world.cpp | 96 --- .../test/test_all_valid.cpp | 8 +- .../collision_detection_fcl/CMakeLists.txt | 6 +- .../collision_common.h | 2 +- .../collision_detector_allocator_fcl.h | 7 +- .../collision_env_fcl.h | 157 +++++ .../collision_robot_fcl.h | 97 --- .../collision_world_fcl.h | 98 --- .../src/collision_env_fcl.cpp | 434 +++++++++++++ .../src/collision_robot_fcl.cpp | 307 --------- .../src/collision_world_fcl.cpp | 299 --------- .../test/test_fcl_collision_detection.cpp | 111 ++-- .../test/test_fcl_env.cpp | 324 ++++++++++ .../collision_distance_field/CMakeLists.txt | 6 +- .../collision_common_distance_field.h | 2 +- ...lision_detector_allocator_distance_field.h | 8 +- .../collision_detector_allocator_hybrid.h | 8 +- ...field.h => collision_env_distance_field.h} | 208 +++--- .../collision_env_hybrid.h | 153 +++++ .../collision_robot_hybrid.h | 98 --- .../collision_world_distance_field.h | 200 ------ .../collision_world_hybrid.h | 116 ---- ...d.cpp => collision_env_distance_field.cpp} | 595 +++++++++++++++--- .../src/collision_env_hybrid.cpp | 185 ++++++ .../src/collision_robot_hybrid.cpp | 96 --- .../src/collision_world_distance_field.cpp | 568 ----------------- .../src/collision_world_hybrid.cpp | 160 ----- .../test/test_collision_distance_field.cpp | 56 +- .../kinematic_constraint.h | 4 +- .../src/kinematic_constraint.cpp | 12 +- .../moveit/planning_scene/planning_scene.h | 61 +- .../planning_scene/src/planning_scene.cpp | 183 ++---- .../chomp_motion_planner/chomp_optimizer.h | 6 +- .../src/chomp_optimizer.cpp | 19 +- .../sbpl_interface/environment_chain3d.h | 6 +- .../src/environment_chain3d.cpp | 27 +- .../src/planning_scene_monitor.cpp | 8 +- .../motion_planning_frame.h | 2 +- .../src/motion_planning_frame_objects.cpp | 12 +- .../src/planning_scene_render.cpp | 2 +- 54 files changed, 2401 insertions(+), 3415 deletions(-) rename moveit_core/collision_detection/include/moveit/collision_detection/allvalid/{collision_world_allvalid.h => collision_env_allvalid.h} (57%) delete mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h rename moveit_core/collision_detection/include/moveit/collision_detection/{collision_robot.h => collision_env.h} (60%) delete mode 100644 moveit_core/collision_detection/include/moveit/collision_detection/collision_world.h rename moveit_core/collision_detection/src/allvalid/{collision_world_allvalid.cpp => collision_env_allvalid.cpp} (53%) delete mode 100644 moveit_core/collision_detection/src/allvalid/collision_robot_allvalid.cpp rename moveit_core/collision_detection/src/{collision_robot.cpp => collision_env.cpp} (66%) delete mode 100644 moveit_core/collision_detection/src/collision_world.cpp create mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h delete mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h delete mode 100644 moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h create mode 100644 moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp delete mode 100644 moveit_core/collision_detection_fcl/src/collision_robot_fcl.cpp delete mode 100644 moveit_core/collision_detection_fcl/src/collision_world_fcl.cpp create mode 100644 moveit_core/collision_detection_fcl/test/test_fcl_env.cpp rename moveit_core/collision_distance_field/include/moveit/collision_distance_field/{collision_robot_distance_field.h => collision_env_distance_field.h} (57%) create mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h delete mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h delete mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h delete mode 100644 moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h rename moveit_core/collision_distance_field/src/{collision_robot_distance_field.cpp => collision_env_distance_field.cpp} (68%) create mode 100644 moveit_core/collision_distance_field/src/collision_env_hybrid.cpp delete mode 100644 moveit_core/collision_distance_field/src/collision_robot_hybrid.cpp delete mode 100644 moveit_core/collision_distance_field/src/collision_world_distance_field.cpp delete mode 100644 moveit_core/collision_distance_field/src/collision_world_hybrid.cpp diff --git a/MIGRATION.md b/MIGRATION.md index 5eca3c2660..7fe1098d53 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -8,6 +8,7 @@ API changes in MoveIt releases - Moved the example package `moveit_controller_manager_example` into [moveit_tutorials](https://github.com/ros-planning/moveit_tutorials) - Requests to `get_planning_scene` service without explicitly setting "components" now return full scene - `moveit_ros_plannning` no longer depends on `moveit_ros_perception` +- `collision_robot` and `collision_world` are combined into a single `collision_env`. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. `getCollisionRobot[Unpadded] / getCollisionWorld` functions return the new combined environment and will be deprecated in the future. ## ROS Melodic diff --git a/moveit_core/collision_detection/CMakeLists.txt b/moveit_core/collision_detection/CMakeLists.txt index 21d3bcb5d3..262db3780d 100644 --- a/moveit_core/collision_detection/CMakeLists.txt +++ b/moveit_core/collision_detection/CMakeLists.txt @@ -1,15 +1,13 @@ set(MOVEIT_LIB_NAME moveit_collision_detection) add_library(${MOVEIT_LIB_NAME} - src/allvalid/collision_robot_allvalid.cpp - src/allvalid/collision_world_allvalid.cpp + src/allvalid/collision_env_allvalid.cpp src/collision_matrix.cpp src/collision_octomap_filter.cpp - src/collision_robot.cpp src/collision_tools.cpp - src/collision_world.cpp src/world.cpp src/world_diff.cpp + src/collision_env.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h index 0382b492d7..7782670035 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_detector_allocator_allvalid.h @@ -37,17 +37,15 @@ #pragma once #include -#include -#include +#include namespace collision_detection { /** \brief An allocator for AllValid collision detectors */ class CollisionDetectorAllocatorAllValid - : public CollisionDetectorAllocatorTemplate + : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_world_allvalid.cpp + static const std::string NAME; // defined in collision_env_allvalid.cpp }; } diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h similarity index 57% rename from moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h rename to moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h index dcf045b554..024a59496b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_world_allvalid.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_env_allvalid.h @@ -32,45 +32,45 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -/* Author: Ioan Sucan */ +/* Author: Ioan Sucan, Jia Pan, Jens Petit */ #pragma once -#include +#include namespace collision_detection { -class CollisionRobotAllValid; - -class CollisionWorldAllValid : public CollisionWorld +/** \brief Collision environment which always just returns no collisions. + * + * This can be used to save resources if collision checking is not important. */ +class CollisionEnvAllValid : public CollisionEnv { public: - CollisionWorldAllValid(); - explicit CollisionWorldAllValid(const WorldPtr& world); - CollisionWorldAllValid(const CollisionWorld& other, const WorldPtr& world); + CollisionEnvAllValid(const robot_model::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0); + CollisionEnvAllValid(const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, double padding = 0.0, + double scale = 1.0); + CollisionEnvAllValid(const CollisionEnv& other, const WorldPtr& world); - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const override; - - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const override; - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world, + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const override; + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const override; + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, + const robot_state::RobotState& state2, const AllowedCollisionMatrix& acm) const override; - virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state) const; - virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const; - void distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot, + virtual double distanceRobot(const robot_state::RobotState& state) const; + virtual double distanceRobot(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; + void distanceRobot(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state) const override; - virtual double distanceWorld(const CollisionWorld& world) const; - virtual double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm) const; - void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const override; + + void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const override; + void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const override; + + void distanceSelf(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const override; }; } diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h b/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h deleted file mode 100644 index 9ce0e2dc15..0000000000 --- a/moveit_core/collision_detection/include/moveit/collision_detection/allvalid/collision_robot_allvalid.h +++ /dev/null @@ -1,85 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#pragma once - -#include - -namespace collision_detection -{ -class CollisionRobotAllValid : public CollisionRobot -{ -public: - CollisionRobotAllValid(const robot_model::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0); - CollisionRobotAllValid(const CollisionRobot& other); - - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const AllowedCollisionMatrix& acm) const override; - - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, const robot_state::RobotState& other_state2, - const AllowedCollisionMatrix& acm) const override; - - virtual double distanceSelf(const robot_state::RobotState& state) const; - virtual double distanceSelf(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; - void distanceSelf(const DistanceRequest& req, DistanceResult& res, - const robot_state::RobotState& state) const override; - - virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const; - virtual double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const; - void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const override; -}; -} diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index 018d6be5e0..f1bb41d857 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -36,8 +36,7 @@ #pragma once -#include -#include +#include #include namespace collision_detection @@ -56,22 +55,20 @@ class CollisionDetectorAllocator virtual const std::string& getName() const = 0; /** create a new CollisionWorld for checking collisions with the supplied world. */ - virtual CollisionWorldPtr allocateWorld(const WorldPtr& world) const = 0; + virtual CollisionEnvPtr allocateEnv(const WorldPtr& world, + const robot_model::RobotModelConstPtr& robot_model) const = 0; /** create a new CollisionWorld by copying an existing CollisionWorld of the same type.s * The world must be either the same world as used by \orig or a copy of that world which has not yet been modified. */ - virtual CollisionWorldPtr allocateWorld(const CollisionWorldConstPtr& orig, const WorldPtr& world) const = 0; + virtual CollisionEnvPtr allocateEnv(const CollisionEnvConstPtr& orig, const WorldPtr& world) const = 0; - /** create a new CollisionRobot given a robot_model */ - virtual CollisionRobotPtr allocateRobot(const robot_model::RobotModelConstPtr& robot_model) const = 0; - - /** create a new CollisionRobot by copying an existing CollisionRobot of the same type. */ - virtual CollisionRobotPtr allocateRobot(const CollisionRobotConstPtr& orig) const = 0; + /** create a new CollisionEnv given a robot_model with a new empty world */ + virtual CollisionEnvPtr allocateEnv(const robot_model::RobotModelConstPtr& robot_model) const = 0; }; /** \brief Template class to make it easy to create an allocator for a specific CollisionWorld/CollisionRobot pair. */ -template +template class CollisionDetectorAllocatorTemplate : public CollisionDetectorAllocator { public: @@ -80,24 +77,19 @@ class CollisionDetectorAllocatorTemplate : public CollisionDetectorAllocator return CollisionDetectorAllocatorType::NAME; } - CollisionWorldPtr allocateWorld(const WorldPtr& world) const override - { - return CollisionWorldPtr(new CollisionWorldType(world)); - } - - CollisionWorldPtr allocateWorld(const CollisionWorldConstPtr& orig, const WorldPtr& world) const override + CollisionEnvPtr allocateEnv(const WorldPtr& world, const robot_model::RobotModelConstPtr& robot_model) const override { - return CollisionWorldPtr(new CollisionWorldType(dynamic_cast(*orig), world)); + return CollisionEnvPtr(new CollisionEnvType(robot_model, world)); } - CollisionRobotPtr allocateRobot(const robot_model::RobotModelConstPtr& robot_model) const override + CollisionEnvPtr allocateEnv(const CollisionEnvConstPtr& orig, const WorldPtr& world) const override { - return CollisionRobotPtr(new CollisionRobotType(robot_model)); + return CollisionEnvPtr(new CollisionEnvType(dynamic_cast(*orig), world)); } - CollisionRobotPtr allocateRobot(const CollisionRobotConstPtr& orig) const override + CollisionEnvPtr allocateEnv(const robot_model::RobotModelConstPtr& robot_model) const override { - return CollisionRobotPtr(new CollisionRobotType(dynamic_cast(*orig))); + return CollisionEnvPtr(new CollisionEnvType(robot_model)); } /** Create an allocator for FCL collision detectors */ diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h similarity index 60% rename from moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h rename to moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h index 2249b56c73..c634ca8597 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_robot.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_env.h @@ -14,7 +14,7 @@ * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. - * * Neither the name of Willow Garage nor the names of its + * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * @@ -32,7 +32,7 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -/* Author: Ioan Sucan */ +/* Author: Ioan Sucan, Jens Petit */ #pragma once @@ -41,34 +41,43 @@ #include #include #include +#include namespace collision_detection { -MOVEIT_CLASS_FORWARD(CollisionRobot); +MOVEIT_CLASS_FORWARD(CollisionEnv); -/** @brief This class represents a collision model of the robot and can be used for self collision checks - (to check if the robot is in collision with itself) or in collision checks with a different robot. Collision checks - with - the environment are performed using the CollisionWorld class. */ -class CollisionRobot +/** \brief Provides the interface to the individual collision checking libraries. */ +class CollisionEnv { public: + CollisionEnv() = delete; + /** @brief Constructor * @param model A robot model to construct the collision robot from * @param padding The padding to use for all objects/links on the robot * @scale scale A common scaling to use for all objects/links on the robot */ - CollisionRobot(const robot_model::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0); + CollisionEnv(const robot_model::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0); - /** @brief A copy constructor*/ - CollisionRobot(const CollisionRobot& other); + /** @brief Constructor + * @param model A robot model to construct the collision robot from + * @param padding The padding to use for all objects/links on the robot + * @scale scale A common scaling to use for all objects/links on the robot + */ + CollisionEnv(const robot_model::RobotModelConstPtr& model, const WorldPtr& world, double padding = 0.0, + double scale = 1.0); + + /** \brief Copy constructor */ + CollisionEnv(const CollisionEnv& other, const WorldPtr& world); - virtual ~CollisionRobot() + virtual ~CollisionEnv() { } - /** @brief Check for self collision. Any collision between any pair of links is checked for, NO collisions are + /** @brief Check for robot self collision. Any collision between any pair of links is checked for, NO collisions are * ignored. + * * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result * @param state The kinematic state for which checks are being made */ @@ -84,82 +93,75 @@ class CollisionRobot virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0; - /** @brief Check for self collision in a continuous manner. Any collision between any pair of links is checked for, - * NO collisions are ignored. + /** \brief Check whether the robot model is in collision with itself or the world at a particular state. + * Any collision between any pair of links is checked for, NO collisions are ignored. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made */ - virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const = 0; + * @param state The kinematic state for which checks are being made */ + virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const; - /** \brief Check for self collision. Allowed collisions specified by the allowed collision matrix are - * taken into account. + /** \brief Check whether the robot model is in collision with itself or the world at a particular state. + * Allowed collisions specified by the allowed collision matrix are taken into account. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made + * @param state The kinematic state for which checks are being made * @param acm The allowed collision matrix. */ - virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const = 0; + virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const; - /** \brief Check for collision with a different robot (possibly a different kinematic model as well). - * Any collision between any pair of links is checked for, NO collisions are ignored. + /** \brief Check whether the robot model is in collision with the world. Any collisions between a robot link + * and the world are considered. Self collisions are not checked. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state The kinematic state for which checks are being made. - * @param other_robot The collision representation for the other robot - * @param other_state The kinematic state corresponding to the other robot */ - virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const = 0; - - /** \brief Check for collision with a different robot (possibly a different kinematic model as well). - * Allowed collisions specified by the allowed collision matrix are taken into account. + * @robot robot The collision model for the robot + * @param state The kinematic state for which checks are being made + */ + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const = 0; + + /** \brief Check whether the robot model is in collision with the world. + * Allowed collisions are ignored. Self collisions are not checked. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state The kinematic state for which checks are being made. - * @param other_robot The collision representation for the other robot - * @param other_state The kinematic state corresponding to the other robot - * @param acm The allowed collision matrix. */ - virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const = 0; + * @robot robot The collision model for the robot + * @param state The kinematic state for which checks are being made + * @param acm The allowed collision matrix.*/ + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0; - /** \brief Check for collision with a different robot (possibly a different kinematic model as well), in a continuous - * fashion. - * Any collision between any pair of links is checked for, NO collisions are ignored. + /** \brief Check whether the robot model is in collision with the world in a continuous manner (between two robot + * states). + * Allowed collisions are ignored. Self collisions are not checked. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made (this robot) - * @param state2 The kinematic state at the end of the segment for which checks are being made (this robot) - * @param other_robot The collision representation for the other robot - * @param other_state1 The kinematic state at the start of the segment for which checks are being made (other robot) - * @param other_state2 The kinematic state at the end of the segment for which checks are being made (other robot) */ - virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, + * @robot robot The collision model for the robot + * @param state1 The kinematic state at the start of the segment for which checks are being made + * @param state2 The kinematic state at the end of the segment for which checks are being made + * @param acm The allowed collision matrix.*/ + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2) const = 0; + const AllowedCollisionMatrix& acm) const = 0; - /** \brief Check for collision with a different robot (possibly a different kinematic model as well), in a continuous - * fashion. - * Allowed collisions specified by the allowed collision matrix are taken into account. + /** \brief Check whether the robot model is in collision with the world in a continuous manner (between two robot + * states). + * Allowed collisions are ignored. Self collisions are not checked. * @param req A CollisionRequest object that encapsulates the collision request * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made (this robot) - * @param state2 The kinematic state at the end of the segment for which checks are being made (this robot) - * @param other_robot The collision representation for the other robot - * @param other_state1 The kinematic state at the start of the segment for which checks are being made (other robot) - * @param other_state2 The kinematic state at the end of the segment for which checks are being made (other robot) - * @param acm The allowed collision matrix. */ - virtual void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2, - const AllowedCollisionMatrix& acm) const = 0; + * @robot robot The collision model for the robot + * @param state1 The kinematic state at the start of the segment for which checks are being made + * @param state2 The kinematic state at the end of the segment for which checks are being made + * @param acm The allowed collision matrix.*/ + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const = 0; + + /** \brief The distance to self-collision given the robot is at state \e state. + @param req A DistanceRequest object that encapsulates the distance request + @param res A DistanceResult object that encapsulates the distance result + @param state The state of this robot to consider */ + virtual void distanceSelf(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const = 0; /** \brief The distance to self-collision given the robot is at state \e state. */ inline double distanceSelf(const robot_state::RobotState& state) const @@ -185,58 +187,69 @@ class CollisionRobot return res.minimum_distance.distance; } - /** \brief The distance to self-collision given the robot is at state \e state. - @param req A DistanceRequest object that encapsulates the distance request - @param res A DistanceResult object that encapsulates the distance result - @param state The state of this robot to consider */ - virtual void distanceSelf(const DistanceRequest& req, DistanceResult& res, - const robot_state::RobotState& state) const = 0; - - /** \brief The distance to another robot instance. - - - @param state The state of this robot to consider - @param other_robot The other robot instance to measure distance to - @param other_state The state of the other robot */ - inline double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const + /** \brief Compute the distance between a robot and the world + * @param req A DistanceRequest object that encapsulates the distance request + * @param res A DistanceResult object that encapsulates the distance result + * @param robot The robot to check distance for + * @param state The state for the robot to check distances from */ + virtual void distanceRobot(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const = 0; + + /** \brief Compute the shortest distance between a robot and the world + * @param robot The robot to check distance for + * @param state The state for the robot to check distances from + * @param verbose Output debug information about distance checks */ + inline double distanceRobot(const robot_state::RobotState& state, bool verbose = false) const { DistanceRequest req; DistanceResult res; + req.verbose = verbose; req.enableGroup(getRobotModel()); - distanceOther(req, res, state, other_robot, other_state); + + distanceRobot(req, res, state); return res.minimum_distance.distance; } - /** \brief The distance to another robot instance, ignoring distances between links that are allowed to always - collide. - - - @param state The state of this robot to consider - @param other_robot The other robot instance to measure distance to - @param other_state The state of the other robot - @param acm The collision matrix specifying which links are allowed to always collide */ - inline double distanceOther(const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, const AllowedCollisionMatrix& acm) const + /** \brief Compute the shortest distance between a robot and the world + * @param robot The robot to check distance for + * @param state The state for the robot to check distances from + * @param acm Using an allowed collision matrix has the effect of ignoring distances from links that are always + * allowed to be in collision. + * @param verbose Output debug information about distance checks */ + inline double distanceRobot(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + bool verbose = false) const { DistanceRequest req; DistanceResult res; - req.enableGroup(getRobotModel()); req.acm = &acm; - distanceOther(req, res, state, other_robot, other_state); + req.verbose = verbose; + req.enableGroup(getRobotModel()); + + distanceRobot(req, res, state); return res.minimum_distance.distance; } - /** \brief The distance to self-collision given the robot is at state \e state. - @param req A DistanceRequest object that encapsulates the distance request - @param res A DistanceResult object that encapsulates the distance result - @param state The state of this robot to consider - @param other_robot The other robot instance to measure distance to - @param other_state The state of the other robot */ - virtual void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const = 0; + /** set the world to use. + * This can be expensive unless the new and old world are empty. + * Passing NULL will result in a new empty world being created. */ + virtual void setWorld(const WorldPtr& world); + + /** access the world geometry */ + const WorldPtr& getWorld() + { + return world_; + } + + /** access the world geometry */ + const WorldConstPtr& getWorld() const + { + return world_const_; + } + + typedef World::ObjectPtr ObjectPtr; + typedef World::ObjectConstPtr ObjectConstPtr; /** @brief The kinematic model corresponding to this collision model*/ const robot_model::RobotModelConstPtr& getRobotModel() const @@ -306,5 +319,9 @@ class CollisionRobot /** @brief The internally maintained map (from link names to scaling)*/ std::map link_scale_; + +private: + WorldPtr world_; // The world always valid, never nullptr. + WorldConstPtr world_const_; // always same as world_ }; } diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h index 1460b80ff0..ed36a81113 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_octomap_filter.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include namespace collision_detection { diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h index 5142e41bb9..320265eb6b 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_plugin.h @@ -35,8 +35,7 @@ #pragma once #include -#include -#include +#include #include namespace collision_detection @@ -52,8 +51,7 @@ MOVEIT_CLASS_FORWARD(CollisionPlugin); * { * * class MyCollisionDetectorAllocator : - * public collision_detection::CollisionDetectorAllocatorTemplate + * public collision_detection::CollisionDetectorAllocatorTemplate * { * public: * static const std::string NAME_; diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_world.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_world.h deleted file mode 100644 index 717e72ec09..0000000000 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_world.h +++ /dev/null @@ -1,279 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan, Sachin Chitta */ - -#pragma once - -#include - -#include -#include -#include -#include - -/** \brief Generic interface to collision detection */ -namespace collision_detection -{ -MOVEIT_CLASS_FORWARD(CollisionWorld); - -/** \brief Perform collision checking with the environment. The - * collision world maintains a representation of the environment - * that the robot is operating in. */ -class CollisionWorld : private boost::noncopyable -{ -public: - CollisionWorld(); - - explicit CollisionWorld(const WorldPtr& world); - - /** \brief A copy constructor. \e other should not be changed while the copy constructor is running. - * world must be the same world as used by other or a (not-yet-modified) copy of the world used by other */ - CollisionWorld(const CollisionWorld& other, const WorldPtr& world); - - virtual ~CollisionWorld() - { - } - - /**********************************************************************/ - /* Collision Checking Routines */ - /**********************************************************************/ - - /** \brief Check whether the robot model is in collision with itself or the world at a particular state. - * Any collision between any pair of links is checked for, NO collisions are ignored. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param state The kinematic state for which checks are being made */ - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const; - - /** \brief Check whether the robot model is in collision with itself or the world at a particular state. - * Allowed collisions specified by the allowed collision matrix are taken into account. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param state The kinematic state for which checks are being made - * @param acm The allowed collision matrix. */ - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; - - /** \brief Check whether the robot model is in collision with itself or the world in a continuous manner - * (between two robot states) - * Any collision between any pair of links is checked for, NO collisions are ignored. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made */ - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2) const; - - /** \brief Check whether the robot model is in collision with itself or the world in a continuous manner - * (between two robot states). - * Allowed collisions specified by the allowed collision matrix are taken into account. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made - * @param acm The allowed collision matrix. */ - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const; - - /** \brief Check whether the robot model is in collision with the world. Any collisions between a robot link - * and the world are considered. Self collisions are not checked. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @robot robot The collision model for the robot - * @param state The kinematic state for which checks are being made - */ - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const = 0; - - /** \brief Check whether the robot model is in collision with the world. - * Allowed collisions are ignored. Self collisions are not checked. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @robot robot The collision model for the robot - * @param state The kinematic state for which checks are being made - * @param acm The allowed collision matrix.*/ - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const = 0; - - /** \brief Check whether the robot model is in collision with the world in a continuous manner (between two robot - * states). - * Any collisions between a robot link and the world are considered. Self collisions are not checked. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @robot robot The collision model for the robot - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made */ - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const = 0; - - /** \brief Check whether the robot model is in collision with the world in a continuous manner (between two robot - * states). - * Allowed collisions are ignored. Self collisions are not checked. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @robot robot The collision model for the robot - * @param state1 The kinematic state at the start of the segment for which checks are being made - * @param state2 The kinematic state at the end of the segment for which checks are being made - * @param acm The allowed collision matrix.*/ - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const = 0; - - /** \brief Check whether a given set of objects is in collision with objects from another world. - * Any contacts are considered. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param other_world The other collision world - */ - virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const = 0; - - /** \brief Check whether a given set of objects is in collision with objects from another world. - * Allowed collisions are ignored. Any contacts are considered. - * @param req A CollisionRequest object that encapsulates the collision request - * @param res A CollisionResult object that encapsulates the collision result - * @param other_world The other collision world - * @param acm The allowed collision matrix.*/ - virtual void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world, - const AllowedCollisionMatrix& acm) const = 0; - - /** \brief Compute the shortest distance between a robot and the world - * @param robot The robot to check distance for - * @param state The state for the robot to check distances from - * @param verbose Output debug information about distance checks */ - inline double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state, - bool verbose = false) const - { - DistanceRequest req; - DistanceResult res; - - req.verbose = verbose; - req.enableGroup(robot.getRobotModel()); - - distanceRobot(req, res, robot, state); - return res.minimum_distance.distance; - } - - /** \brief Compute the shortest distance between a robot and the world - * @param robot The robot to check distance for - * @param state The state for the robot to check distances from - * @param acm Using an allowed collision matrix has the effect of ignoring distances from links that are always - * allowed to be in collision. - * @param verbose Output debug information about distance checks */ - inline double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, bool verbose = false) const - { - DistanceRequest req; - DistanceResult res; - - req.acm = &acm; - req.verbose = verbose; - req.enableGroup(robot.getRobotModel()); - - distanceRobot(req, res, robot, state); - return res.minimum_distance.distance; - } - - /** \brief Compute the distance between a robot and the world - * @param req A DistanceRequest object that encapsulates the distance request - * @param res A DistanceResult object that encapsulates the distance result - * @param robot The robot to check distance for - * @param state The state for the robot to check distances from */ - virtual void distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const = 0; - - /** \brief The shortest distance to another world instance (\e world) - * @param verbose Output debug information about distance checks */ - inline double distanceWorld(const CollisionWorld& world, bool verbose = false) const - { - DistanceRequest req; - DistanceResult res; - - req.verbose = verbose; - distanceWorld(req, res, world); - - return res.minimum_distance.distance; - } - - /** \brief The shortest distance to another world instance (\e world), ignoring the distances between world elements - * that are allowed to collide (as specified by \e acm) - * @param verbose Output debug information about distance checks */ - inline double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm, - bool verbose = false) const - { - DistanceRequest req; - DistanceResult res; - - req.acm = &acm; - req.verbose = verbose; - distanceWorld(req, res, world); - - return res.minimum_distance.distance; - } - - /** \brief Compute the distance between another world - * @param req A DistanceRequest object that encapsulates the distance request - * @param res A DistanceResult object that encapsulates the distance result - * @param world The world to check distance for */ - virtual void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const = 0; - - /** set the world to use. - * This can be expensive unless the new and old world are empty. - * Passing NULL will result in a new empty world being created. */ - virtual void setWorld(const WorldPtr& world); - - /** access the world geometry */ - const WorldPtr& getWorld() - { - return world_; - } - - /** access the world geometry */ - const WorldConstPtr& getWorld() const - { - return world_const_; - } - - typedef World::ObjectPtr ObjectPtr; - typedef World::ObjectConstPtr ObjectConstPtr; - -private: - WorldPtr world_; // The world. Always valid. Never NULL. - WorldConstPtr world_const_; // always same as world_ -}; -} diff --git a/moveit_core/collision_detection/src/allvalid/collision_world_allvalid.cpp b/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp similarity index 53% rename from moveit_core/collision_detection/src/allvalid/collision_world_allvalid.cpp rename to moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp index 023f308a62..bf84110b23 100644 --- a/moveit_core/collision_detection/src/allvalid/collision_world_allvalid.cpp +++ b/moveit_core/collision_detection/src/allvalid/collision_env_allvalid.cpp @@ -32,118 +32,104 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -/* Author: Ioan Sucan */ +/* Author: Ioan Sucan, Jia Pan, Jens Petit */ -#include +#include +#include -collision_detection::CollisionWorldAllValid::CollisionWorldAllValid() : CollisionWorld() -{ -} +const std::string collision_detection::CollisionDetectorAllocatorAllValid::NAME("ALL_VALID"); -collision_detection::CollisionWorldAllValid::CollisionWorldAllValid(const WorldPtr& world) : CollisionWorld(world) +collision_detection::CollisionEnvAllValid::CollisionEnvAllValid(const robot_model::RobotModelConstPtr& robot_model, + double padding, double scale) + : CollisionEnv(robot_model, padding, scale) { } -collision_detection::CollisionWorldAllValid::CollisionWorldAllValid(const CollisionWorld& other, const WorldPtr& world) - : CollisionWorld(other, world) +collision_detection::CollisionEnvAllValid::CollisionEnvAllValid(const robot_model::RobotModelConstPtr& robot_model, + const WorldPtr& world, double padding, double scale) + : CollisionEnv(robot_model, world, padding, scale) { } -void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state) const +collision_detection::CollisionEnvAllValid::CollisionEnvAllValid(const CollisionEnv& other, const WorldPtr& world) + : CollisionEnv(other, world) { - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const +void collision_detection::CollisionEnvAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const { res.collision = false; if (req.verbose) ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const +void collision_detection::CollisionEnvAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const { res.collision = false; if (req.verbose) ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const +void collision_detection::CollisionEnvAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const { res.collision = false; if (req.verbose) ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const +void collision_detection::CollisionEnvAllValid::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2, + const AllowedCollisionMatrix& acm) const { res.collision = false; if (req.verbose) ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world, - const AllowedCollisionMatrix& acm) const +void collision_detection::CollisionEnvAllValid::distanceRobot(const collision_detection::DistanceRequest& req, + collision_detection::DistanceResult& res, + const moveit::core::RobotState& state) const { res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -double collision_detection::CollisionWorldAllValid::distanceRobot(const CollisionRobot& robot, - const robot_state::RobotState& state) const +double collision_detection::CollisionEnvAllValid::distanceRobot(const robot_state::RobotState& state) const { return 0.0; } -double collision_detection::CollisionWorldAllValid::distanceRobot(const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const +double collision_detection::CollisionEnvAllValid::distanceRobot(const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const { return 0.0; } -void collision_detection::CollisionWorldAllValid::distanceRobot(const collision_detection::DistanceRequest& req, - collision_detection::DistanceResult& res, - const collision_detection::CollisionRobot& robot, - const moveit::core::RobotState& state) const +void collision_detection::CollisionEnvAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const { res.collision = false; + if (req.verbose) + ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -double collision_detection::CollisionWorldAllValid::distanceWorld(const CollisionWorld& world) const -{ - return 0.0; -} - -double collision_detection::CollisionWorldAllValid::distanceWorld(const CollisionWorld& world, - const AllowedCollisionMatrix& acm) const +void collision_detection::CollisionEnvAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const { - return 0.0; + res.collision = false; + if (req.verbose) + ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); } -void collision_detection::CollisionWorldAllValid::distanceWorld(const collision_detection::DistanceRequest& req, - collision_detection::DistanceResult& res, - const collision_detection::CollisionWorld& world) const +void collision_detection::CollisionEnvAllValid::distanceSelf(const collision_detection::DistanceRequest& req, + collision_detection::DistanceResult& res, + const moveit::core::RobotState& state) const { res.collision = false; } - -#include -const std::string collision_detection::CollisionDetectorAllocatorAllValid::NAME("ALL_VALID"); diff --git a/moveit_core/collision_detection/src/allvalid/collision_robot_allvalid.cpp b/moveit_core/collision_detection/src/allvalid/collision_robot_allvalid.cpp deleted file mode 100644 index 963f374711..0000000000 --- a/moveit_core/collision_detection/src/allvalid/collision_robot_allvalid.cpp +++ /dev/null @@ -1,171 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan, Jia Pan */ - -#include - -collision_detection::CollisionRobotAllValid::CollisionRobotAllValid(const robot_model::RobotModelConstPtr& robot_model, - double padding, double scale) - : CollisionRobot(robot_model, padding, scale) -{ -} - -collision_detection::CollisionRobotAllValid::CollisionRobotAllValid(const CollisionRobot& other) : CollisionRobot(other) -{ -} - -void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -void collision_detection::CollisionRobotAllValid::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2, - const AllowedCollisionMatrix& acm) const -{ - res.collision = false; - if (req.verbose) - ROS_INFO_NAMED("collision_detection", "Using AllValid collision detection. No collision checking is performed."); -} - -double collision_detection::CollisionRobotAllValid::distanceSelf(const robot_state::RobotState& state) const -{ - return 0.0; -} - -double collision_detection::CollisionRobotAllValid::distanceSelf(const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - return 0.0; -} - -void collision_detection::CollisionRobotAllValid::distanceSelf(const collision_detection::DistanceRequest& req, - collision_detection::DistanceResult& res, - const moveit::core::RobotState& state) const -{ - res.collision = false; -} - -double collision_detection::CollisionRobotAllValid::distanceOther(const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const -{ - return 0.0; -} - -double collision_detection::CollisionRobotAllValid::distanceOther(const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const -{ - return 0.0; -} - -void collision_detection::CollisionRobotAllValid::distanceOther(const collision_detection::DistanceRequest& req, - collision_detection::DistanceResult& res, - const moveit::core::RobotState& state, - const collision_detection::CollisionRobot& other_robot, - const moveit::core::RobotState& other_state) const -{ - res.collision = false; -} diff --git a/moveit_core/collision_detection/src/collision_robot.cpp b/moveit_core/collision_detection/src/collision_env.cpp similarity index 66% rename from moveit_core/collision_detection/src/collision_robot.cpp rename to moveit_core/collision_detection/src/collision_env.cpp index c3e27751a6..131b25676c 100644 --- a/moveit_core/collision_detection/src/collision_robot.cpp +++ b/moveit_core/collision_detection/src/collision_env.cpp @@ -14,7 +14,7 @@ * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. - * * Neither the name of Willow Garage nor the names of its + * * Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * @@ -32,9 +32,9 @@ * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ -/* Author: Ioan Sucan */ +/* Author: Ioan Sucan, Jens Petit */ -#include +#include #include static inline bool validateScale(double scale) @@ -69,8 +69,8 @@ static inline bool validatePadding(double padding) namespace collision_detection { -CollisionRobot::CollisionRobot(const robot_model::RobotModelConstPtr& model, double padding, double scale) - : robot_model_(model) +CollisionEnv::CollisionEnv(const robot_model::RobotModelConstPtr& model, double padding, double scale) + : robot_model_(model), world_(new World()), world_const_(world_) { if (!validateScale(scale)) scale = 1.0; @@ -85,13 +85,30 @@ CollisionRobot::CollisionRobot(const robot_model::RobotModelConstPtr& model, dou } } -CollisionRobot::CollisionRobot(const CollisionRobot& other) : robot_model_(other.robot_model_) +CollisionEnv::CollisionEnv(const robot_model::RobotModelConstPtr& model, const WorldPtr& world, double padding, + double scale) + : robot_model_(model), world_(world), world_const_(world_) +{ + if (!validateScale(scale)) + scale = 1.0; + if (!validatePadding(padding)) + padding = 0.0; + + const std::vector& links = robot_model_->getLinkModelsWithCollisionGeometry(); + for (auto link : links) + { + link_padding_[link->getName()] = padding; + link_scale_[link->getName()] = scale; + } +} + +CollisionEnv::CollisionEnv(const CollisionEnv& other, const WorldPtr& world) + : robot_model_(other.robot_model_), world_(world), world_const_(world) { link_padding_ = other.link_padding_; link_scale_ = other.link_scale_; } - -void CollisionRobot::setPadding(double padding) +void CollisionEnv::setPadding(double padding) { if (!validatePadding(padding)) return; @@ -107,7 +124,7 @@ void CollisionRobot::setPadding(double padding) updatedPaddingOrScaling(u); } -void CollisionRobot::setScale(double scale) +void CollisionEnv::setScale(double scale) { if (!validateScale(scale)) return; @@ -123,8 +140,9 @@ void CollisionRobot::setScale(double scale) updatedPaddingOrScaling(u); } -void CollisionRobot::setLinkPadding(const std::string& link_name, double padding) +void CollisionEnv::setLinkPadding(const std::string& link_name, double padding) { + validatePadding(padding); bool update = getLinkPadding(link_name) != padding; link_padding_[link_name] = padding; if (update) @@ -134,7 +152,7 @@ void CollisionRobot::setLinkPadding(const std::string& link_name, double padding } } -double CollisionRobot::getLinkPadding(const std::string& link_name) const +double CollisionEnv::getLinkPadding(const std::string& link_name) const { auto it = link_padding_.find(link_name); if (it != link_padding_.end()) @@ -143,11 +161,12 @@ double CollisionRobot::getLinkPadding(const std::string& link_name) const return 0.0; } -void CollisionRobot::setLinkPadding(const std::map& padding) +void CollisionEnv::setLinkPadding(const std::map& padding) { std::vector u; for (const auto& link_pad_pair : padding) { + validatePadding(link_pad_pair.second); bool update = getLinkPadding(link_pad_pair.first) != link_pad_pair.second; link_padding_[link_pad_pair.first] = link_pad_pair.second; if (update) @@ -157,13 +176,14 @@ void CollisionRobot::setLinkPadding(const std::map& padding updatedPaddingOrScaling(u); } -const std::map& CollisionRobot::getLinkPadding() const +const std::map& CollisionEnv::getLinkPadding() const { return link_padding_; } -void CollisionRobot::setLinkScale(const std::string& link_name, double scale) +void CollisionEnv::setLinkScale(const std::string& link_name, double scale) { + validateScale(scale); bool update = getLinkScale(link_name) != scale; link_scale_[link_name] = scale; if (update) @@ -173,7 +193,7 @@ void CollisionRobot::setLinkScale(const std::string& link_name, double scale) } } -double CollisionRobot::getLinkScale(const std::string& link_name) const +double CollisionEnv::getLinkScale(const std::string& link_name) const { auto it = link_scale_.find(link_name); if (it != link_scale_.end()) @@ -182,7 +202,7 @@ double CollisionRobot::getLinkScale(const std::string& link_name) const return 1.0; } -void CollisionRobot::setLinkScale(const std::map& scale) +void CollisionEnv::setLinkScale(const std::map& scale) { std::vector u; for (const auto& link_scale_pair : scale) @@ -196,16 +216,17 @@ void CollisionRobot::setLinkScale(const std::map& scale) updatedPaddingOrScaling(u); } -const std::map& CollisionRobot::getLinkScale() const +const std::map& CollisionEnv::getLinkScale() const { return link_scale_; } -void CollisionRobot::setPadding(const std::vector& padding) +void CollisionEnv::setPadding(const std::vector& padding) { std::vector u; for (const auto& p : padding) { + validatePadding(p.padding); bool update = getLinkPadding(p.link_name) != p.padding; link_padding_[p.link_name] = p.padding; if (update) @@ -215,11 +236,12 @@ void CollisionRobot::setPadding(const std::vector& pad updatedPaddingOrScaling(u); } -void CollisionRobot::setScale(const std::vector& scale) +void CollisionEnv::setScale(const std::vector& scale) { std::vector u; for (const auto& s : scale) { + validateScale(s.scale); bool update = getLinkScale(s.link_name) != s.scale; link_scale_[s.link_name] = s.scale; if (update) @@ -229,7 +251,7 @@ void CollisionRobot::setScale(const std::vector& scale) updatedPaddingOrScaling(u); } -void CollisionRobot::getPadding(std::vector& padding) const +void CollisionEnv::getPadding(std::vector& padding) const { padding.clear(); for (const auto& lp : link_padding_) @@ -241,7 +263,7 @@ void CollisionRobot::getPadding(std::vector& padding) } } -void CollisionRobot::getScale(std::vector& scale) const +void CollisionEnv::getScale(std::vector& scale) const { scale.clear(); for (const auto& ls : link_scale_) @@ -253,8 +275,33 @@ void CollisionRobot::getScale(std::vector& scale) const } } -void CollisionRobot::updatedPaddingOrScaling(const std::vector& links) +void CollisionEnv::updatedPaddingOrScaling(const std::vector& links) +{ +} + +void CollisionEnv::setWorld(const WorldPtr& world) +{ + world_ = world; + if (!world_) + world_.reset(new World()); + + world_const_ = world; +} + +void CollisionEnv::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + checkSelfCollision(req, res, state); + if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) + checkRobotCollision(req, res, state); +} + +void CollisionEnv::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const { + checkSelfCollision(req, res, state, acm); + if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) + checkRobotCollision(req, res, state, acm); } } // end of namespace collision_detection diff --git a/moveit_core/collision_detection/src/collision_octomap_filter.cpp b/moveit_core/collision_detection/src/collision_octomap_filter.cpp index 5305727973..051a7afd25 100644 --- a/moveit_core/collision_detection/src/collision_octomap_filter.cpp +++ b/moveit_core/collision_detection/src/collision_octomap_filter.cpp @@ -36,7 +36,6 @@ #include #include -#include #include #include #include diff --git a/moveit_core/collision_detection/src/collision_world.cpp b/moveit_core/collision_detection/src/collision_world.cpp deleted file mode 100644 index ec2f3abcf9..0000000000 --- a/moveit_core/collision_detection/src/collision_world.cpp +++ /dev/null @@ -1,96 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#include -#include - -namespace collision_detection -{ -CollisionWorld::CollisionWorld() : world_(new World()), world_const_(world_) -{ -} - -CollisionWorld::CollisionWorld(const WorldPtr& world) : world_(world), world_const_(world) -{ -} - -CollisionWorld::CollisionWorld(const CollisionWorld& other, const WorldPtr& world) : world_(world), world_const_(world) -{ -} - -void CollisionWorld::checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - robot.checkSelfCollision(req, res, state); - if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) - checkRobotCollision(req, res, robot, state); -} - -void CollisionWorld::checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const -{ - robot.checkSelfCollision(req, res, state, acm); - if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) - checkRobotCollision(req, res, robot, state, acm); -} - -void CollisionWorld::checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2) const -{ - robot.checkSelfCollision(req, res, state1, state2); - if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) - checkRobotCollision(req, res, robot, state1, state2); -} - -void CollisionWorld::checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const -{ - robot.checkSelfCollision(req, res, state1, state2, acm); - if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) - checkRobotCollision(req, res, robot, state1, state2, acm); -} - -void CollisionWorld::setWorld(const WorldPtr& world) -{ - world_ = world; - if (!world_) - world_.reset(new World()); - - world_const_ = world; -} - -} // end of namespace collision_detection \ No newline at end of file diff --git a/moveit_core/collision_detection/test/test_all_valid.cpp b/moveit_core/collision_detection/test/test_all_valid.cpp index 47a33a81cf..435f473980 100644 --- a/moveit_core/collision_detection/test/test_all_valid.cpp +++ b/moveit_core/collision_detection/test/test_all_valid.cpp @@ -36,14 +36,12 @@ #include #include -#include -#include +#include TEST(AllValid, Instantiate) { using namespace collision_detection; CollisionDetectorAllocatorAllValid allocator; - CollisionWorldAllValid world; urdf::ModelInterfaceSharedPtr urdf_model; urdf_model.reset(new urdf::ModelInterface()); @@ -51,11 +49,11 @@ TEST(AllValid, Instantiate) srdf_model.reset(new srdf::Model()); robot_model::RobotModelConstPtr robot_model; robot_model.reset(new robot_model::RobotModel(urdf_model, srdf_model)); - CollisionRobotAllValid robot(robot_model); + CollisionEnvAllValid env(robot_model); } int main(int argc, char** argv) { testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); -} \ No newline at end of file +} diff --git a/moveit_core/collision_detection_fcl/CMakeLists.txt b/moveit_core/collision_detection_fcl/CMakeLists.txt index 74149b6552..939f958d32 100644 --- a/moveit_core/collision_detection_fcl/CMakeLists.txt +++ b/moveit_core/collision_detection_fcl/CMakeLists.txt @@ -2,8 +2,7 @@ set(MOVEIT_LIB_NAME moveit_collision_detection_fcl) add_library(${MOVEIT_LIB_NAME} src/collision_common.cpp - src/collision_robot_fcl.cpp - src/collision_world_fcl.cpp + src/collision_env_fcl.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") @@ -30,4 +29,7 @@ if(CATKIN_ENABLE_TESTING) catkin_add_gtest(test_fcl_collision_detection test/test_fcl_collision_detection.cpp) target_link_libraries(test_fcl_collision_detection moveit_test_utils ${MOVEIT_LIB_NAME} ${Boost_LIBRARIES}) + + catkin_add_gtest(test_fcl_collision_env test/test_fcl_env.cpp) + target_link_libraries(test_fcl_collision_env moveit_test_utils ${MOVEIT_LIB_NAME} ${Boost_LIBRARIES}) endif() diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 347a9426d1..87fd375580 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -37,7 +37,7 @@ #pragma once #include -#include +#include #include #include diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h index a72b4fd5d6..88bcfcddae 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_detector_allocator_fcl.h @@ -37,16 +37,15 @@ #pragma once #include -#include -#include +#include namespace collision_detection { /** \brief An allocator for FCL collision detectors */ class CollisionDetectorAllocatorFCL - : public CollisionDetectorAllocatorTemplate + : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_world_fcl.cpp + static const std::string NAME; // defined in collision_env_fcl.cpp }; } diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h new file mode 100644 index 0000000000..b2819a6147 --- /dev/null +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -0,0 +1,157 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Ioan Sucan, Jens Petit */ + +#pragma once + +#include +#include + +#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) +#include +#else +#include +#endif + +#include + +namespace collision_detection +{ +/** \brief FCL implementation of the CollisionEnv */ +class CollisionEnvFCL : public CollisionEnv +{ +public: + CollisionEnvFCL() = delete; + + CollisionEnvFCL(const robot_model::RobotModelConstPtr& model, double padding = 0.0, double scale = 1.0); + + CollisionEnvFCL(const robot_model::RobotModelConstPtr& model, const WorldPtr& world, double padding = 0.0, + double scale = 1.0); + + CollisionEnvFCL(const CollisionEnvFCL& other, const WorldPtr& world); + + ~CollisionEnvFCL() override; + + virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const override; + + virtual void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, const robot_state::RobotState& state2, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const override; + + virtual void distanceSelf(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const override; + + virtual void distanceRobot(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const override; + + void setWorld(const WorldPtr& world) override; + +protected: + /** \brief Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot links + */ + void updatedPaddingOrScaling(const std::vector& links) override; + + /** \brief Bundles the different checkSelfCollision functions into a single function */ + void checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm) const; + + void checkRobotCollisionHelper(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix* acm) const; + + /** \brief Construct an FCL collision object from MoveIt's World::Object. */ + void constructFCLObjectWorld(const World::Object* obj, FCLObject& fcl_obj) const; + + /** \brief Updates the specified object in \m fcl_objs_ and in the manager from new data available in the World. + * + * If it does not exist in world, it is deleted. If it's not existing in \m fcl_objs_ yet, it's added there. */ + void updateFCLObject(const std::string& id); + + /** \brief Out of the current robot state and its attached bodies construct an FCLObject which can then be used to + * check for collision. + * + * The current state is used to recalculate the AABB of the FCL collision objects. However they are not computed from + * scratch (which would require call to computeLocalAABB()) but are only transformed according to the joint states. + * + * \param state The current robot state + * \param fcl_obj The newly filled object */ + void constructFCLObjectRobot(const robot_state::RobotState& state, FCLObject& fcl_obj) const; + + /** \brief Prepares for the collision check through constructing an FCL collision object out of the current robot + * state and specifying a broadphase collision manager of FCL where the constructed object is registered to. */ + void allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const; + + /** \brief Converts all shapes which make up an atttached body into a vector of FCLGeometryConstPtr. + * + * When they are converted, they can be added to the FCL representation of the robot for collision checking. + * + * \param ab Pointer to the attached body + * \param geoms Output vector of geometries + */ + void getAttachedBodyObjects(const robot_state::AttachedBody* ab, std::vector& geoms) const; + + /** \brief Vector of shared pointers to the FCL geometry for the objects in fcl_objs_. */ + std::vector robot_geoms_; + + /** \brief Vector of shared pointers to the FCL collision objects which make up the robot */ + std::vector robot_fcl_objs_; + + /// FCL collision manager which handles the collision checking process + std::unique_ptr manager_; + + std::map fcl_objs_; + +private: + /** \brief Callback function executed for each change to the world environment */ + void notifyObjectChange(const ObjectConstPtr& obj, World::Action action); + + World::ObserverHandle observer_handle_; +}; +} diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h deleted file mode 100644 index 917658bab3..0000000000 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_robot_fcl.h +++ /dev/null @@ -1,97 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#pragma once - -#include - -namespace collision_detection -{ -class CollisionRobotFCL : public CollisionRobot -{ - friend class CollisionWorldFCL; - -public: - CollisionRobotFCL(const robot_model::RobotModelConstPtr& robot_model, double padding = 0.0, double scale = 1.0); - - CollisionRobotFCL(const CollisionRobotFCL& other); - - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const override; - void checkSelfCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const AllowedCollisionMatrix& acm) const override; - - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2) const override; - void checkOtherCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, const robot_state::RobotState& other_state2, - const AllowedCollisionMatrix& acm) const override; - - void distanceSelf(const DistanceRequest& req, DistanceResult& res, - const robot_state::RobotState& state) const override; - - void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const override; - -protected: - void updatedPaddingOrScaling(const std::vector& links) override; - void constructFCLObject(const robot_state::RobotState& state, FCLObject& fcl_obj) const; - void allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const; - void getAttachedBodyObjects(const robot_state::AttachedBody* ab, std::vector& geoms) const; - - void checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm) const; - void checkOtherCollisionHelper(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, const AllowedCollisionMatrix* acm) const; - - std::vector geoms_; - std::vector fcl_objs_; -}; -} diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h deleted file mode 100644 index 65cc476471..0000000000 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_world_fcl.h +++ /dev/null @@ -1,98 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#pragma once - -#include -#include - -#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) -#include -#else -#include -#endif - -#include - -namespace collision_detection -{ -class CollisionWorldFCL : public CollisionWorld -{ -public: - CollisionWorldFCL(); - explicit CollisionWorldFCL(const WorldPtr& world); - CollisionWorldFCL(const CollisionWorldFCL& other, const WorldPtr& world); - ~CollisionWorldFCL() override; - - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2) const override; - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const override; - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const override; - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world, - const AllowedCollisionMatrix& acm) const override; - - void distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const override; - - void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const override; - - void setWorld(const WorldPtr& world) override; - -protected: - void checkWorldCollisionHelper(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world, - const AllowedCollisionMatrix* acm) const; - void checkRobotCollisionHelper(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix* acm) const; - - void constructFCLObject(const World::Object* obj, FCLObject& fcl_obj) const; - void updateFCLObject(const std::string& id); - - std::unique_ptr manager_; - std::map fcl_objs_; - -private: - void initialize(); - void notifyObjectChange(const ObjectConstPtr& obj, World::Action action); - World::ObserverHandle observer_handle_; -}; -} diff --git a/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp new file mode 100644 index 0000000000..20ef171fbc --- /dev/null +++ b/moveit_core/collision_detection_fcl/src/collision_env_fcl.cpp @@ -0,0 +1,434 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Ioan Sucan, Jens Petit */ + +#include +#include +#include + +#include + +#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) +#include +#endif + +namespace collision_detection +{ +const std::string CollisionDetectorAllocatorFCL::NAME("FCL"); + +CollisionEnvFCL::CollisionEnvFCL(const robot_model::RobotModelConstPtr& model, double padding, double scale) + : CollisionEnv(model, padding, scale) +{ + const std::vector& links = robot_model_->getLinkModelsWithCollisionGeometry(); + std::size_t index; + robot_geoms_.resize(robot_model_->getLinkGeometryCount()); + robot_fcl_objs_.resize(robot_model_->getLinkGeometryCount()); + // we keep the same order of objects as what RobotState *::getLinkState() returns + for (auto link : links) + for (std::size_t j = 0; j < link->getShapes().size(); ++j) + { + FCLGeometryConstPtr link_geometry = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()), + getLinkPadding(link->getName()), link, j); + if (link_geometry) + { + index = link->getFirstCollisionBodyTransformIndex() + j; + robot_geoms_[index] = link_geometry; + + // Need to store the FCL object so the AABB does not get recreated every time. + // Every time this object is created, g->computeLocalAABB() is called which is + // very expensive and should only be calculated once. To update the AABB, use the + // collObj->setTransform and then call collObj->computeAABB() to transform the AABB. + robot_fcl_objs_[index] = + FCLCollisionObjectConstPtr(new fcl::CollisionObjectd(link_geometry->collision_geometry_)); + } + else + ROS_ERROR_NAMED("collision_detection.fcl", "Unable to construct collision geometry for link '%s'", + link->getName().c_str()); + } + + auto m = new fcl::DynamicAABBTreeCollisionManagerd(); + // m->tree_init_level = 2; + manager_.reset(m); + + // request notifications about changes to new world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2)); +} + +CollisionEnvFCL::CollisionEnvFCL(const robot_model::RobotModelConstPtr& model, const WorldPtr& world, double padding, + double scale) + : CollisionEnv(model, world, padding, scale) +{ + const std::vector& links = robot_model_->getLinkModelsWithCollisionGeometry(); + std::size_t index; + robot_geoms_.resize(robot_model_->getLinkGeometryCount()); + robot_fcl_objs_.resize(robot_model_->getLinkGeometryCount()); + // we keep the same order of objects as what RobotState *::getLinkState() returns + for (auto link : links) + for (std::size_t j = 0; j < link->getShapes().size(); ++j) + { + FCLGeometryConstPtr g = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()), + getLinkPadding(link->getName()), link, j); + if (g) + { + index = link->getFirstCollisionBodyTransformIndex() + j; + robot_geoms_[index] = g; + + // Need to store the FCL object so the AABB does not get recreated every time. + // Every time this object is created, g->computeLocalAABB() is called which is + // very expensive and should only be calculated once. To update the AABB, use the + // collObj->setTransform and then call collObj->computeAABB() to transform the AABB. + robot_fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObjectd(g->collision_geometry_)); + } + else + ROS_ERROR_NAMED("collision_detection.fcl", "Unable to construct collision geometry for link '%s'", + link->getName().c_str()); + } + + auto m = new fcl::DynamicAABBTreeCollisionManagerd(); + // m->tree_init_level = 2; + manager_.reset(m); + + // request notifications about changes to new world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2)); + getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); +} + +CollisionEnvFCL::~CollisionEnvFCL() +{ + getWorld()->removeObserver(observer_handle_); +} + +CollisionEnvFCL::CollisionEnvFCL(const CollisionEnvFCL& other, const WorldPtr& world) : CollisionEnv(other, world) +{ + robot_geoms_ = other.robot_geoms_; + robot_fcl_objs_ = other.robot_fcl_objs_; + + auto m = new fcl::DynamicAABBTreeCollisionManagerd(); + // m->tree_init_level = 2; + manager_.reset(m); + + fcl_objs_ = other.fcl_objs_; + for (auto& fcl_obj : fcl_objs_) + fcl_obj.second.registerTo(manager_.get()); + // manager_->update(); + + // request notifications about changes to new world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2)); +} + +void CollisionEnvFCL::getAttachedBodyObjects(const robot_state::AttachedBody* ab, + std::vector& geoms) const +{ + const std::vector& shapes = ab->getShapes(); + for (std::size_t i = 0; i < shapes.size(); ++i) + { + FCLGeometryConstPtr co = createCollisionGeometry(shapes[i], ab, i); + if (co) + geoms.push_back(co); + } +} + +void CollisionEnvFCL::constructFCLObjectWorld(const World::Object* obj, FCLObject& fcl_obj) const +{ + for (std::size_t i = 0; i < obj->shapes_.size(); ++i) + { + FCLGeometryConstPtr g = createCollisionGeometry(obj->shapes_[i], obj); + if (g) + { + auto co = new fcl::CollisionObjectd(g->collision_geometry_, transform2fcl(obj->shape_poses_[i])); + fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(co)); + fcl_obj.collision_geometry_.push_back(g); + } + } +} + +void CollisionEnvFCL::constructFCLObjectRobot(const robot_state::RobotState& state, FCLObject& fcl_obj) const +{ + fcl_obj.collision_objects_.reserve(robot_geoms_.size()); + fcl::Transform3d fcl_tf; + + for (std::size_t i = 0; i < robot_geoms_.size(); ++i) + if (robot_geoms_[i] && robot_geoms_[i]->collision_geometry_) + { + transform2fcl(state.getCollisionBodyTransform(robot_geoms_[i]->collision_geometry_data_->ptr.link, + robot_geoms_[i]->collision_geometry_data_->shape_index), + fcl_tf); + auto coll_obj = new fcl::CollisionObjectd(*robot_fcl_objs_[i]); + coll_obj->setTransform(fcl_tf); + coll_obj->computeAABB(); + fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(coll_obj)); + } + + // TODO: Implement a method for caching fcl::CollisionObject's for robot_state::AttachedBody's + std::vector ab; + state.getAttachedBodies(ab); + for (auto& body : ab) + { + std::vector objs; + getAttachedBodyObjects(body, objs); + const EigenSTL::vector_Isometry3d& ab_t = body->getGlobalCollisionBodyTransforms(); + for (std::size_t k = 0; k < objs.size(); ++k) + if (objs[k]->collision_geometry_) + { + transform2fcl(ab_t[k], fcl_tf); + fcl_obj.collision_objects_.push_back( + FCLCollisionObjectPtr(new fcl::CollisionObjectd(objs[k]->collision_geometry_, fcl_tf))); + // we copy the shared ptr to the CollisionGeometryData, as this is not stored by the class itself, + // and would be destroyed when objs goes out of scope. + fcl_obj.collision_geometry_.push_back(objs[k]); + } + } +} + +void CollisionEnvFCL::allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const +{ + auto m = new fcl::DynamicAABBTreeCollisionManagerd(); + // m->tree_init_level = 2; + manager.manager_.reset(m); + constructFCLObjectRobot(state, manager.object_); + manager.object_.registerTo(manager.manager_.get()); + // manager.manager_->update(); +} + +void CollisionEnvFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + checkSelfCollisionHelper(req, res, state, nullptr); +} + +void CollisionEnvFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const +{ + checkSelfCollisionHelper(req, res, state, &acm); +} + +void CollisionEnvFCL::checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm) const +{ + FCLManager manager; + allocSelfCollisionBroadPhase(state, manager); + CollisionData cd(&req, &res, acm); + cd.enableGroup(getRobotModel()); + manager.manager_->collide(&cd, &collisionCallback); + if (req.distance) + { + DistanceRequest dreq; + DistanceResult dres; + + dreq.group_name = req.group_name; + dreq.acm = acm; + dreq.enableGroup(getRobotModel()); + distanceSelf(dreq, dres, state); + res.distance = dres.minimum_distance.distance; + } +} + +void CollisionEnvFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + checkRobotCollisionHelper(req, res, state, nullptr); +} + +void CollisionEnvFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const +{ + checkRobotCollisionHelper(req, res, state, &acm); +} + +void CollisionEnvFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const +{ + ROS_ERROR_NAMED("collision_detection.bullet", "Continuous collision not implemented"); +} + +void CollisionEnvFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, const robot_state::RobotState& state2, + const AllowedCollisionMatrix& acm) const +{ + ROS_ERROR_NAMED("collision_detection.fcl", "Not implemented"); +} + +void CollisionEnvFCL::checkRobotCollisionHelper(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm) const +{ + FCLObject fcl_obj; + constructFCLObjectRobot(state, fcl_obj); + + CollisionData cd(&req, &res, acm); + cd.enableGroup(getRobotModel()); + for (std::size_t i = 0; !cd.done_ && i < fcl_obj.collision_objects_.size(); ++i) + manager_->collide(fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback); + + if (req.distance) + { + DistanceRequest dreq; + DistanceResult dres; + + dreq.group_name = req.group_name; + dreq.acm = acm; + dreq.enableGroup(getRobotModel()); + distanceRobot(dreq, dres, state); + res.distance = dres.minimum_distance.distance; + } +} + +void CollisionEnvFCL::distanceSelf(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const +{ + FCLManager manager; + allocSelfCollisionBroadPhase(state, manager); + DistanceData drd(&req, &res); + + manager.manager_->distance(&drd, &distanceCallback); +} + +void CollisionEnvFCL::distanceRobot(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const +{ + FCLObject fcl_obj; + constructFCLObjectRobot(state, fcl_obj); + + DistanceData drd(&req, &res); + for (std::size_t i = 0; !drd.done && i < fcl_obj.collision_objects_.size(); ++i) + manager_->distance(fcl_obj.collision_objects_[i].get(), &drd, &distanceCallback); +} + +void CollisionEnvFCL::updateFCLObject(const std::string& id) +{ + // remove FCL objects that correspond to this object + auto jt = fcl_objs_.find(id); + if (jt != fcl_objs_.end()) + { + jt->second.unregisterFrom(manager_.get()); + jt->second.clear(); + } + + // check to see if we have this object + auto it = getWorld()->find(id); + if (it != getWorld()->end()) + { + // construct FCL objects that correspond to this object + if (jt != fcl_objs_.end()) + { + constructFCLObjectWorld(it->second.get(), jt->second); + jt->second.registerTo(manager_.get()); + } + else + { + constructFCLObjectWorld(it->second.get(), fcl_objs_[id]); + fcl_objs_[id].registerTo(manager_.get()); + } + } + else + { + if (jt != fcl_objs_.end()) + fcl_objs_.erase(jt); + } + + // manager_->update(); +} + +void CollisionEnvFCL::setWorld(const WorldPtr& world) +{ + if (world == getWorld()) + return; + + // turn off notifications about old world + getWorld()->removeObserver(observer_handle_); + + // clear out objects from old world + manager_->clear(); + fcl_objs_.clear(); + cleanCollisionGeometryCache(); + + CollisionEnv::setWorld(world); + + // request notifications about changes to new world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvFCL::notifyObjectChange, this, _1, _2)); + + // get notifications any objects already in the new world + getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); +} + +void CollisionEnvFCL::notifyObjectChange(const ObjectConstPtr& obj, World::Action action) +{ + if (action == World::DESTROY) + { + auto it = fcl_objs_.find(obj->id_); + if (it != fcl_objs_.end()) + { + it->second.unregisterFrom(manager_.get()); + it->second.clear(); + fcl_objs_.erase(it); + } + cleanCollisionGeometryCache(); + } + else + { + updateFCLObject(obj->id_); + if (action & (World::DESTROY | World::REMOVE_SHAPE)) + cleanCollisionGeometryCache(); + } +} + +void CollisionEnvFCL::updatedPaddingOrScaling(const std::vector& links) +{ + std::size_t index; + for (const auto& link : links) + { + const robot_model::LinkModel* lmodel = robot_model_->getLinkModel(link); + if (lmodel) + { + for (std::size_t j = 0; j < lmodel->getShapes().size(); ++j) + { + FCLGeometryConstPtr g = createCollisionGeometry(lmodel->getShapes()[j], getLinkScale(lmodel->getName()), + getLinkPadding(lmodel->getName()), lmodel, j); + if (g) + { + index = lmodel->getFirstCollisionBodyTransformIndex() + j; + robot_geoms_[index] = g; + robot_fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObjectd(g->collision_geometry_)); + } + } + } + else + ROS_ERROR_NAMED("collision_detection.fcl", "Updating padding or scaling for unknown link: '%s'", link.c_str()); + } +} + +} // end of namespace collision_detection diff --git a/moveit_core/collision_detection_fcl/src/collision_robot_fcl.cpp b/moveit_core/collision_detection_fcl/src/collision_robot_fcl.cpp deleted file mode 100644 index 9b8a4cea68..0000000000 --- a/moveit_core/collision_detection_fcl/src/collision_robot_fcl.cpp +++ /dev/null @@ -1,307 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#include -#include - -#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) -#include -#endif - -namespace collision_detection -{ -CollisionRobotFCL::CollisionRobotFCL(const robot_model::RobotModelConstPtr& model, double padding, double scale) - : CollisionRobot(model, padding, scale) -{ - const std::vector& links = robot_model_->getLinkModelsWithCollisionGeometry(); - std::size_t index; - geoms_.resize(robot_model_->getLinkGeometryCount()); - fcl_objs_.resize(robot_model_->getLinkGeometryCount()); - // we keep the same order of objects as what RobotState *::getLinkState() returns - for (auto link : links) - for (std::size_t j = 0; j < link->getShapes().size(); ++j) - { - FCLGeometryConstPtr g = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()), - getLinkPadding(link->getName()), link, j); - if (g) - { - index = link->getFirstCollisionBodyTransformIndex() + j; - geoms_[index] = g; - - // Need to store the FCL object so the AABB does not get recreated every time. - // Every time this object is created, g->computeLocalAABB() is called which is - // very expensive and should only be calculated once. To update the AABB, use the - // collObj->setTransform and then call collObj->computeAABB() to transform the AABB. - fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObjectd(g->collision_geometry_)); - } - else - ROS_ERROR_NAMED("collision_detection.fcl", "Unable to construct collision geometry for link '%s'", - link->getName().c_str()); - } -} - -CollisionRobotFCL::CollisionRobotFCL(const CollisionRobotFCL& other) : CollisionRobot(other) -{ - geoms_ = other.geoms_; - fcl_objs_ = other.fcl_objs_; -} - -void CollisionRobotFCL::getAttachedBodyObjects(const robot_state::AttachedBody* ab, - std::vector& geoms) const -{ - const std::vector& shapes = ab->getShapes(); - for (std::size_t i = 0; i < shapes.size(); ++i) - { - FCLGeometryConstPtr co = createCollisionGeometry(shapes[i], ab, i); - if (co) - geoms.push_back(co); - } -} - -void CollisionRobotFCL::constructFCLObject(const robot_state::RobotState& state, FCLObject& fcl_obj) const -{ - fcl_obj.collision_objects_.reserve(geoms_.size()); - fcl::Transform3d fcl_tf; - - for (std::size_t i = 0; i < geoms_.size(); ++i) - if (geoms_[i] && geoms_[i]->collision_geometry_) - { - transform2fcl(state.getCollisionBodyTransform(geoms_[i]->collision_geometry_data_->ptr.link, - geoms_[i]->collision_geometry_data_->shape_index), - fcl_tf); - auto coll_obj = new fcl::CollisionObjectd(*fcl_objs_[i]); - coll_obj->setTransform(fcl_tf); - coll_obj->computeAABB(); - fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(coll_obj)); - } - - // TODO: Implement a method for caching fcl::CollisionObject's for robot_state::AttachedBody's - std::vector ab; - state.getAttachedBodies(ab); - for (auto& body : ab) - { - std::vector objs; - getAttachedBodyObjects(body, objs); - const EigenSTL::vector_Isometry3d& ab_t = body->getGlobalCollisionBodyTransforms(); - for (std::size_t k = 0; k < objs.size(); ++k) - if (objs[k]->collision_geometry_) - { - transform2fcl(ab_t[k], fcl_tf); - fcl_obj.collision_objects_.push_back( - FCLCollisionObjectPtr(new fcl::CollisionObjectd(objs[k]->collision_geometry_, fcl_tf))); - // we copy the shared ptr to the CollisionGeometryData, as this is not stored by the class itself, - // and would be destroyed when objs goes out of scope. - fcl_obj.collision_geometry_.push_back(objs[k]); - } - } -} - -void CollisionRobotFCL::allocSelfCollisionBroadPhase(const robot_state::RobotState& state, FCLManager& manager) const -{ - auto m = new fcl::DynamicAABBTreeCollisionManagerd(); - // m->tree_init_level = 2; - manager.manager_.reset(m); - constructFCLObject(state, manager.object_); - manager.object_.registerTo(manager.manager_.get()); - // manager.manager_->update(); -} - -void CollisionRobotFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state) const -{ - checkSelfCollisionHelper(req, res, state, nullptr); -} - -void CollisionRobotFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - checkSelfCollisionHelper(req, res, state, &acm); -} - -void CollisionRobotFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionRobotFCL::checkSelfCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionRobotFCL::checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm) const -{ - FCLManager manager; - allocSelfCollisionBroadPhase(state, manager); - CollisionData cd(&req, &res, acm); - cd.enableGroup(getRobotModel()); - manager.manager_->collide(&cd, &collisionCallback); - if (req.distance) - { - DistanceRequest dreq; - DistanceResult dres; - - dreq.group_name = req.group_name; - dreq.acm = acm; - dreq.enableGroup(getRobotModel()); - distanceSelf(dreq, dres, state); - res.distance = dres.minimum_distance.distance; - } -} - -void CollisionRobotFCL::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const -{ - checkOtherCollisionHelper(req, res, state, other_robot, other_state, nullptr); -} - -void CollisionRobotFCL::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, - const AllowedCollisionMatrix& acm) const -{ - checkOtherCollisionHelper(req, res, state, other_robot, other_state, &acm); -} - -void CollisionRobotFCL::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionRobotFCL::checkOtherCollision(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state1, - const robot_state::RobotState& state2, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state1, - const robot_state::RobotState& other_state2, - const AllowedCollisionMatrix& acm) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionRobotFCL::checkOtherCollisionHelper(const CollisionRequest& req, CollisionResult& res, - const robot_state::RobotState& state, - const CollisionRobot& other_robot, - const robot_state::RobotState& other_state, - const AllowedCollisionMatrix* acm) const -{ - FCLManager manager; - allocSelfCollisionBroadPhase(state, manager); - - const CollisionRobotFCL& fcl_rob = dynamic_cast(other_robot); - FCLObject other_fcl_obj; - fcl_rob.constructFCLObject(other_state, other_fcl_obj); - - CollisionData cd(&req, &res, acm); - cd.enableGroup(getRobotModel()); - for (std::size_t i = 0; !cd.done_ && i < other_fcl_obj.collision_objects_.size(); ++i) - manager.manager_->collide(other_fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback); - - if (req.distance) - { - DistanceRequest dreq; - DistanceResult dres; - - dreq.group_name = req.group_name; - dreq.acm = acm; - dreq.enableGroup(getRobotModel()); - distanceOther(dreq, dres, state, other_robot, other_state); - res.distance = dres.minimum_distance.distance; - } -} - -void CollisionRobotFCL::updatedPaddingOrScaling(const std::vector& links) -{ - std::size_t index; - for (const auto& link : links) - { - const robot_model::LinkModel* lmodel = robot_model_->getLinkModel(link); - if (lmodel) - { - for (std::size_t j = 0; j < lmodel->getShapes().size(); ++j) - { - FCLGeometryConstPtr g = createCollisionGeometry(lmodel->getShapes()[j], getLinkScale(lmodel->getName()), - getLinkPadding(lmodel->getName()), lmodel, j); - if (g) - { - index = lmodel->getFirstCollisionBodyTransformIndex() + j; - geoms_[index] = g; - fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObjectd(g->collision_geometry_)); - } - } - } - else - ROS_ERROR_NAMED("collision_detection.fcl", "Updating padding or scaling for unknown link: '%s'", link.c_str()); - } -} - -void CollisionRobotFCL::distanceSelf(const DistanceRequest& req, DistanceResult& res, - const robot_state::RobotState& state) const -{ - FCLManager manager; - allocSelfCollisionBroadPhase(state, manager); - DistanceData drd(&req, &res); - - manager.manager_->distance(&drd, &distanceCallback); -} - -void CollisionRobotFCL::distanceOther(const DistanceRequest& req, DistanceResult& res, - const robot_state::RobotState& state, const CollisionRobot& other_robot, - const robot_state::RobotState& other_state) const -{ - FCLManager manager; - allocSelfCollisionBroadPhase(state, manager); - - const CollisionRobotFCL& fcl_rob = dynamic_cast(other_robot); - FCLObject other_fcl_obj; - fcl_rob.constructFCLObject(other_state, other_fcl_obj); - - DistanceData drd(&req, &res); - for (std::size_t i = 0; !drd.done && i < other_fcl_obj.collision_objects_.size(); ++i) - manager.manager_->distance(other_fcl_obj.collision_objects_[i].get(), &drd, &distanceCallback); -} - -} // end of namespace collision_detection diff --git a/moveit_core/collision_detection_fcl/src/collision_world_fcl.cpp b/moveit_core/collision_detection_fcl/src/collision_world_fcl.cpp deleted file mode 100644 index 8d6eb392f9..0000000000 --- a/moveit_core/collision_detection_fcl/src/collision_world_fcl.cpp +++ /dev/null @@ -1,299 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Ioan Sucan */ - -#include -#include -#include - -#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) -#include -#include -#include -#include -#else -#include -#include -#include -#include -#endif - -#include - -namespace collision_detection -{ -const std::string CollisionDetectorAllocatorFCL::NAME("FCL"); - -CollisionWorldFCL::CollisionWorldFCL() : CollisionWorld() -{ - auto m = new fcl::DynamicAABBTreeCollisionManagerd(); - // m->tree_init_level = 2; - manager_.reset(m); - - // request notifications about changes to new world - observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldFCL::notifyObjectChange, this, _1, _2)); -} - -CollisionWorldFCL::CollisionWorldFCL(const WorldPtr& world) : CollisionWorld(world) -{ - auto m = new fcl::DynamicAABBTreeCollisionManagerd(); - // m->tree_init_level = 2; - manager_.reset(m); - - // request notifications about changes to new world - observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldFCL::notifyObjectChange, this, _1, _2)); - getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); -} - -CollisionWorldFCL::CollisionWorldFCL(const CollisionWorldFCL& other, const WorldPtr& world) - : CollisionWorld(other, world) -{ - auto m = new fcl::DynamicAABBTreeCollisionManagerd(); - // m->tree_init_level = 2; - manager_.reset(m); - - fcl_objs_ = other.fcl_objs_; - for (auto& fcl_obj : fcl_objs_) - fcl_obj.second.registerTo(manager_.get()); - // manager_->update(); - - // request notifications about changes to new world - observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldFCL::notifyObjectChange, this, _1, _2)); -} - -CollisionWorldFCL::~CollisionWorldFCL() -{ - getWorld()->removeObserver(observer_handle_); -} - -void CollisionWorldFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state) const -{ - checkRobotCollisionHelper(req, res, robot, state, nullptr); -} - -void CollisionWorldFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - checkRobotCollisionHelper(req, res, robot, state, &acm); -} - -void CollisionWorldFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state1, - const robot_state::RobotState& state2) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionWorldFCL::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state1, - const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const -{ - ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented"); -} - -void CollisionWorldFCL::checkRobotCollisionHelper(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm) const -{ - const CollisionRobotFCL& robot_fcl = dynamic_cast(robot); - FCLObject fcl_obj; - robot_fcl.constructFCLObject(state, fcl_obj); - - CollisionData cd(&req, &res, acm); - cd.enableGroup(robot.getRobotModel()); - for (std::size_t i = 0; !cd.done_ && i < fcl_obj.collision_objects_.size(); ++i) - manager_->collide(fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback); - - if (req.distance) - { - DistanceRequest dreq; - DistanceResult dres; - - dreq.group_name = req.group_name; - dreq.acm = acm; - dreq.enableGroup(robot.getRobotModel()); - distanceRobot(dreq, dres, robot, state); - res.distance = dres.minimum_distance.distance; - } -} - -void CollisionWorldFCL::checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const -{ - checkWorldCollisionHelper(req, res, other_world, nullptr); -} - -void CollisionWorldFCL::checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world, const AllowedCollisionMatrix& acm) const -{ - checkWorldCollisionHelper(req, res, other_world, &acm); -} - -void CollisionWorldFCL::checkWorldCollisionHelper(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world, - const AllowedCollisionMatrix* acm) const -{ - const CollisionWorldFCL& other_fcl_world = dynamic_cast(other_world); - CollisionData cd(&req, &res, acm); - manager_->collide(other_fcl_world.manager_.get(), &cd, &collisionCallback); - - if (req.distance) - { - DistanceRequest dreq; - DistanceResult dres; - - dreq.group_name = req.group_name; - dreq.acm = acm; - distanceWorld(dreq, dres, other_world); - res.distance = dres.minimum_distance.distance; - } -} - -void CollisionWorldFCL::constructFCLObject(const World::Object* obj, FCLObject& fcl_obj) const -{ - for (std::size_t i = 0; i < obj->shapes_.size(); ++i) - { - FCLGeometryConstPtr g = createCollisionGeometry(obj->shapes_[i], obj); - if (g) - { - auto co = new fcl::CollisionObjectd(g->collision_geometry_, transform2fcl(obj->shape_poses_[i])); - fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(co)); - fcl_obj.collision_geometry_.push_back(g); - } - } -} - -void CollisionWorldFCL::updateFCLObject(const std::string& id) -{ - // remove FCL objects that correspond to this object - auto jt = fcl_objs_.find(id); - if (jt != fcl_objs_.end()) - { - jt->second.unregisterFrom(manager_.get()); - jt->second.clear(); - } - - // check to see if we have this object - auto it = getWorld()->find(id); - if (it != getWorld()->end()) - { - // construct FCL objects that correspond to this object - if (jt != fcl_objs_.end()) - { - constructFCLObject(it->second.get(), jt->second); - jt->second.registerTo(manager_.get()); - } - else - { - constructFCLObject(it->second.get(), fcl_objs_[id]); - fcl_objs_[id].registerTo(manager_.get()); - } - } - else - { - if (jt != fcl_objs_.end()) - fcl_objs_.erase(jt); - } - - // manager_->update(); -} - -void CollisionWorldFCL::setWorld(const WorldPtr& world) -{ - if (world == getWorld()) - return; - - // turn off notifications about old world - getWorld()->removeObserver(observer_handle_); - - // clear out objects from old world - manager_->clear(); - fcl_objs_.clear(); - cleanCollisionGeometryCache(); - - CollisionWorld::setWorld(world); - - // request notifications about changes to new world - observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionWorldFCL::notifyObjectChange, this, _1, _2)); - - // get notifications any objects already in the new world - getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); -} - -void CollisionWorldFCL::notifyObjectChange(const ObjectConstPtr& obj, World::Action action) -{ - if (action == World::DESTROY) - { - auto it = fcl_objs_.find(obj->id_); - if (it != fcl_objs_.end()) - { - it->second.unregisterFrom(manager_.get()); - it->second.clear(); - fcl_objs_.erase(it); - } - cleanCollisionGeometryCache(); - } - else - { - updateFCLObject(obj->id_); - if (action & (World::DESTROY | World::REMOVE_SHAPE)) - cleanCollisionGeometryCache(); - } -} - -void CollisionWorldFCL::distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - const CollisionRobotFCL& robot_fcl = dynamic_cast(robot); - FCLObject fcl_obj; - robot_fcl.constructFCLObject(state, fcl_obj); - - DistanceData drd(&req, &res); - for (std::size_t i = 0; !drd.done && i < fcl_obj.collision_objects_.size(); ++i) - manager_->distance(fcl_obj.collision_objects_[i].get(), &drd, &distanceCallback); -} - -void CollisionWorldFCL::distanceWorld(const DistanceRequest& req, DistanceResult& res, - const CollisionWorld& world) const -{ - const CollisionWorldFCL& other_fcl_world = dynamic_cast(world); - DistanceData drd(&req, &res); - manager_->distance(other_fcl_world.manager_.get(), &drd, &distanceCallback); -} - -} // end of namespace collision_detection diff --git a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection.cpp b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection.cpp index e606f632a3..e4ea360a95 100644 --- a/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection.cpp +++ b/moveit_core/collision_detection_fcl/test/test_fcl_collision_detection.cpp @@ -36,8 +36,7 @@ #include #include -#include -#include +#include #include #include @@ -49,8 +48,7 @@ #include #include -typedef collision_detection::CollisionWorldFCL DefaultCWorldType; -typedef collision_detection::CollisionRobotFCL DefaultCRobotType; +typedef collision_detection::CollisionEnvFCL DefaultEnvType; class FclCollisionDetectionTester : public testing::Test { @@ -63,8 +61,7 @@ class FclCollisionDetectionTester : public testing::Test acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), true)); - crobot_.reset(new DefaultCRobotType(robot_model_)); - cworld_.reset(new DefaultCWorldType()); + c_env_.reset(new DefaultEnvType(robot_model_)); } void TearDown() override @@ -76,8 +73,7 @@ class FclCollisionDetectionTester : public testing::Test robot_model::RobotModelPtr robot_model_; - collision_detection::CollisionRobotPtr crobot_; - collision_detection::CollisionWorldPtr cworld_; + collision_detection::CollisionEnvPtr c_env_; collision_detection::AllowedCollisionMatrixPtr acm_; @@ -97,7 +93,7 @@ TEST_F(FclCollisionDetectionTester, DefaultNotInCollision) collision_detection::CollisionRequest req; collision_detection::CollisionResult res; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_FALSE(res.collision); } @@ -124,11 +120,11 @@ TEST_F(FclCollisionDetectionTester, LinksInCollision) robot_state.update(); acm_->setEntry("base_link", "base_bellow_link", false); - crobot_->checkSelfCollision(req, res1, robot_state, *acm_); + c_env_->checkSelfCollision(req, res1, robot_state, *acm_); ASSERT_TRUE(res1.collision); acm_->setEntry("base_link", "base_bellow_link", true); - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + c_env_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_FALSE(res2.collision); // req.verbose = true; @@ -139,7 +135,7 @@ TEST_F(FclCollisionDetectionTester, LinksInCollision) robot_state.update(); acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); - crobot_->checkSelfCollision(req, res3, robot_state, *acm_); + c_env_->checkSelfCollision(req, res3, robot_state, *acm_); ASSERT_TRUE(res3.collision); } @@ -171,7 +167,7 @@ TEST_F(FclCollisionDetectionTester, ContactReporting) acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); collision_detection::CollisionResult res; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_EQ(res.contacts.size(), 1u); EXPECT_EQ(res.contacts.begin()->second.size(), 1u); @@ -180,7 +176,7 @@ TEST_F(FclCollisionDetectionTester, ContactReporting) req.max_contacts = 2; req.max_contacts_per_pair = 1; // req.verbose = true; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_EQ(res.contacts.size(), 2u); EXPECT_EQ(res.contacts.begin()->second.size(), 1u); @@ -191,7 +187,7 @@ TEST_F(FclCollisionDetectionTester, ContactReporting) req.max_contacts = 10; req.max_contacts_per_pair = 2; acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), false)); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_LE(res.contacts.size(), 10u); EXPECT_LE(res.contact_count, 10u); @@ -222,7 +218,7 @@ TEST_F(FclCollisionDetectionTester, ContactPositions) acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); collision_detection::CollisionResult res; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); ASSERT_EQ(res.contacts.size(), 1u); ASSERT_EQ(res.contacts.begin()->second.size(), 1u); @@ -242,7 +238,7 @@ TEST_F(FclCollisionDetectionTester, ContactPositions) robot_state.update(); collision_detection::CollisionResult res2; - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + c_env_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_TRUE(res2.collision); ASSERT_EQ(res2.contacts.size(), 1u); ASSERT_EQ(res2.contacts.begin()->second.size(), 1u); @@ -262,7 +258,7 @@ TEST_F(FclCollisionDetectionTester, ContactPositions) robot_state.update(); collision_detection::CollisionResult res3; - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + c_env_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_FALSE(res3.collision); } @@ -283,18 +279,18 @@ TEST_F(FclCollisionDetectionTester, AttachedBodyTester) // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(pos1); robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1); robot_state.update(); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_FALSE(res.collision); shapes::Shape* shape = new shapes::Box(.1, .1, .1); - cworld_->getWorld()->addToObject("box", shapes::ShapeConstPtr(shape), pos1); + c_env_->getWorld()->addToObject("box", shapes::ShapeConstPtr(shape), pos1); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + c_env_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); // deletes shape - cworld_->getWorld()->removeObject("box"); + c_env_->getWorld()->removeObject("box"); shape = new shapes::Box(.1, .1, .1); std::vector shapes; @@ -305,7 +301,7 @@ TEST_F(FclCollisionDetectionTester, AttachedBodyTester) robot_state.attachBody("box", shapes, poses, touch_links, "r_gripper_palm_link"); res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); // deletes shape @@ -318,19 +314,19 @@ TEST_F(FclCollisionDetectionTester, AttachedBodyTester) robot_state.update(); res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + c_env_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_FALSE(res.collision); pos1.translation().x() = 5.01; shapes::Shape* coll = new shapes::Box(.1, .1, .1); - cworld_->getWorld()->addToObject("coll", shapes::ShapeConstPtr(coll), pos1); + c_env_->getWorld()->addToObject("coll", shapes::ShapeConstPtr(coll), pos1); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + c_env_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); acm_->setEntry("coll", "r_gripper_palm_link", true); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + c_env_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); } @@ -342,15 +338,15 @@ TEST_F(FclCollisionDetectionTester, DiffSceneTester) collision_detection::CollisionRequest req; collision_detection::CollisionResult res; - - collision_detection::CollisionRobotFCL new_crobot( - *(dynamic_cast(crobot_.get()))); + collision_detection::CollisionEnvFCL* casted_env_pointer = + dynamic_cast(c_env_.get()); + collision_detection::CollisionEnvFCL new_c_env(*casted_env_pointer, c_env_->getWorld()); ros::WallTime before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); double first_check = (ros::WallTime::now() - before).toSec(); before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); double second_check = (ros::WallTime::now() - before).toSec(); EXPECT_LT(fabs(first_check - second_check), .05); @@ -367,22 +363,21 @@ TEST_F(FclCollisionDetectionTester, DiffSceneTester) robot_state.attachBody("kinect", shapes, poses, touch_links, "r_gripper_palm_link"); before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); first_check = (ros::WallTime::now() - before).toSec(); before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); second_check = (ros::WallTime::now() - before).toSec(); // the first check is going to take a while, as data must be constructed EXPECT_LT(second_check, .1); - collision_detection::CollisionRobotFCL other_new_crobot( - *(dynamic_cast(crobot_.get()))); + collision_detection::CollisionEnvFCL other_new_c_env(*casted_env_pointer, c_env_->getWorld()); before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); first_check = (ros::WallTime::now() - before).toSec(); before = ros::WallTime::now(); - new_crobot.checkSelfCollision(req, res, robot_state); + new_c_env.checkSelfCollision(req, res, robot_state); second_check = (ros::WallTime::now() - before).toSec(); EXPECT_LT(fabs(first_check - second_check), .05); @@ -398,23 +393,23 @@ TEST_F(FclCollisionDetectionTester, ConvertObjectToAttached) Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity(); pos2.translation().x() = 10.0; - cworld_->getWorld()->addToObject("kinect", shape, pos1); + c_env_->getWorld()->addToObject("kinect", shape, pos1); robot_state::RobotState robot_state(robot_model_); robot_state.setToDefaultValues(); robot_state.update(); ros::WallTime before = ros::WallTime::now(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state); + c_env_->checkRobotCollision(req, res, robot_state); double first_check = (ros::WallTime::now() - before).toSec(); before = ros::WallTime::now(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state); + c_env_->checkRobotCollision(req, res, robot_state); double second_check = (ros::WallTime::now() - before).toSec(); EXPECT_LT(second_check, .05); - collision_detection::CollisionWorld::ObjectConstPtr object = cworld_->getWorld()->getObject("kinect"); - cworld_->getWorld()->removeObject("kinect"); + collision_detection::CollisionEnv::ObjectConstPtr object = c_env_->getWorld()->getObject("kinect"); + c_env_->getWorld()->removeObject("kinect"); robot_state::RobotState robot_state1(robot_model_); robot_state::RobotState robot_state2(robot_model_); @@ -434,17 +429,17 @@ TEST_F(FclCollisionDetectionTester, ConvertObjectToAttached) // going to take a while, but that's fine res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state1); + c_env_->checkSelfCollision(req, res, robot_state1); EXPECT_TRUE(res.collision); before = ros::WallTime::now(); - crobot_->checkSelfCollision(req, res, robot_state1, *acm_); + c_env_->checkSelfCollision(req, res, robot_state1, *acm_); first_check = (ros::WallTime::now() - before).toSec(); before = ros::WallTime::now(); req.verbose = true; res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state2, *acm_); + c_env_->checkSelfCollision(req, res, robot_state2, *acm_); second_check = (ros::WallTime::now() - before).toSec(); EXPECT_LT(first_check, .05); @@ -461,7 +456,7 @@ TEST_F(FclCollisionDetectionTester, TestCollisionMapAdditionSpeed) shapes.push_back(shapes::ShapeConstPtr(new shapes::Box(.01, .01, .01))); } ros::WallTime start = ros::WallTime::now(); - cworld_->getWorld()->addToObject("map", shapes, poses); + c_env_->getWorld()->addToObject("map", shapes, poses); double t = (ros::WallTime::now() - start).toSec(); EXPECT_GE(1.0, t); // this is not really a failure; it is just that slow; @@ -480,16 +475,16 @@ TEST_F(FclCollisionDetectionTester, MoveMesh) shapes::ShapePtr kinect_shape; kinect_shape.reset(shapes::createMeshFromResource(kinect_dae_resource_)); - cworld_->getWorld()->addToObject("kinect", kinect_shape, kinect_pose); + c_env_->getWorld()->addToObject("kinect", kinect_shape, kinect_pose); Eigen::Isometry3d np; for (unsigned int i = 0; i < 5; i++) { np = Eigen::Translation3d(i * .001, i * .001, i * .001) * Eigen::Quaterniond::Identity(); - cworld_->getWorld()->moveShapeInObject("kinect", kinect_shape, np); + c_env_->getWorld()->moveShapeInObject("kinect", kinect_shape, np); collision_detection::CollisionRequest req; collision_detection::CollisionResult res; - cworld_->checkCollision(req, res, *crobot_, robot_state1, *acm_); + c_env_->checkCollision(req, res, robot_state1, *acm_); } } @@ -508,37 +503,37 @@ TEST_F(FclCollisionDetectionTester, TestChangingShapeSize) std::vector shapes; for (unsigned int i = 0; i < 5; i++) { - cworld_->getWorld()->removeObject("shape"); + c_env_->getWorld()->removeObject("shape"); shapes.clear(); poses.clear(); shapes.push_back(shapes::ShapeConstPtr(new shapes::Box(1 + i * .0001, 1 + i * .0001, 1 + i * .0001))); poses.push_back(Eigen::Isometry3d::Identity()); - cworld_->getWorld()->addToObject("shape", shapes, poses); + c_env_->getWorld()->addToObject("shape", shapes, poses); collision_detection::CollisionRequest req; collision_detection::CollisionResult res; - cworld_->checkCollision(req, res, *crobot_, robot_state1, *acm_); + c_env_->checkCollision(req, res, robot_state1, *acm_); ASSERT_TRUE(res.collision); } Eigen::Isometry3d kinect_pose = Eigen::Isometry3d::Identity(); shapes::ShapePtr kinect_shape; kinect_shape.reset(shapes::createMeshFromResource(kinect_dae_resource_)); - cworld_->getWorld()->addToObject("kinect", kinect_shape, kinect_pose); + c_env_->getWorld()->addToObject("kinect", kinect_shape, kinect_pose); collision_detection::CollisionRequest req2; collision_detection::CollisionResult res2; - cworld_->checkCollision(req2, res2, *crobot_, robot_state1, *acm_); + c_env_->checkCollision(req2, res2, robot_state1, *acm_); ASSERT_TRUE(res2.collision); for (unsigned int i = 0; i < 5; i++) { - cworld_->getWorld()->removeObject("shape"); + c_env_->getWorld()->removeObject("shape"); shapes.clear(); poses.clear(); shapes.push_back(shapes::ShapeConstPtr(new shapes::Box(1 + i * .0001, 1 + i * .0001, 1 + i * .0001))); poses.push_back(Eigen::Isometry3d::Identity()); - cworld_->getWorld()->addToObject("shape", shapes, poses); + c_env_->getWorld()->addToObject("shape", shapes, poses); collision_detection::CollisionRequest req; collision_detection::CollisionResult res; - cworld_->checkCollision(req, res, *crobot_, robot_state1, *acm_); + c_env_->checkCollision(req, res, robot_state1, *acm_); ASSERT_TRUE(res.collision); } } diff --git a/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp b/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp new file mode 100644 index 0000000000..64f65b64c3 --- /dev/null +++ b/moveit_core/collision_detection_fcl/test/test_fcl_env.cpp @@ -0,0 +1,324 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2019, Jens Petit + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Jens Petit */ + +#include +#include + +#include + +#include +#include +#include + +#include +#include + +#include +#include + +/** \brief Brings the panda robot in user defined home position */ +inline void setToHome(robot_state::RobotState& panda_state) +{ + panda_state.setToDefaultValues(); + double joint2 = -0.785; + double joint4 = -2.356; + double joint6 = 1.571; + double joint7 = 0.785; + panda_state.setJointPositions("panda_joint2", &joint2); + panda_state.setJointPositions("panda_joint4", &joint4); + panda_state.setJointPositions("panda_joint6", &joint6); + panda_state.setJointPositions("panda_joint7", &joint7); + panda_state.update(); +} + +class CollisionDetectionEnvTest : public testing::Test +{ +protected: + void SetUp() override + { + robot_model_ = moveit::core::loadTestingRobotModel("panda"); + robot_model_ok_ = static_cast(robot_model_); + + acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), false)); + + acm_->setEntry("panda_link0", "panda_link1", true); + acm_->setEntry("panda_link1", "panda_link2", true); + acm_->setEntry("panda_link2", "panda_link3", true); + acm_->setEntry("panda_link3", "panda_link4", true); + acm_->setEntry("panda_link4", "panda_link5", true); + acm_->setEntry("panda_link5", "panda_link6", true); + acm_->setEntry("panda_link6", "panda_link7", true); + acm_->setEntry("panda_link7", "panda_hand", true); + acm_->setEntry("panda_hand", "panda_rightfinger", true); + acm_->setEntry("panda_hand", "panda_leftfinger", true); + acm_->setEntry("panda_rightfinger", "panda_leftfinger", true); + acm_->setEntry("panda_link5", "panda_link7", true); + acm_->setEntry("panda_link6", "panda_hand", true); + + c_env_.reset(new collision_detection::CollisionEnvFCL(robot_model_)); + + robot_state_.reset(new robot_state::RobotState(robot_model_)); + + setToHome(*robot_state_); + } + + void TearDown() override + { + } + +protected: + bool robot_model_ok_; + + robot_model::RobotModelPtr robot_model_; + + collision_detection::CollisionEnvPtr c_env_; + + collision_detection::AllowedCollisionMatrixPtr acm_; + + robot_state::RobotStatePtr robot_state_; +}; + +/** \brief Correct setup testing. */ +TEST_F(CollisionDetectionEnvTest, InitOK) +{ + ASSERT_TRUE(robot_model_ok_); +} + +/** \brief Tests the default values specified in the SRDF if they are collision free. */ +TEST_F(CollisionDetectionEnvTest, DefaultNotInCollision) +{ + collision_detection::CollisionRequest req; + collision_detection::CollisionResult res; + c_env_->checkSelfCollision(req, res, *robot_state_, *acm_); + ASSERT_FALSE(res.collision); +} + +/** \brief A configuration where the robot should collide with itself. */ +TEST_F(CollisionDetectionEnvTest, LinksInCollision) +{ + // Sets the joint values to zero which is a colliding configuration + robot_state_->setToDefaultValues(); + robot_state_->update(); + + collision_detection::CollisionRequest req; + collision_detection::CollisionResult res; + c_env_->checkSelfCollision(req, res, *robot_state_, *acm_); + ASSERT_TRUE(res.collision); +} + +/** \brief Adding obstacles to the world which are tested against the robot. Simple cases. */ +TEST_F(CollisionDetectionEnvTest, RobotWorldCollision_1) +{ + collision_detection::CollisionRequest req; + collision_detection::CollisionResult res; + + shapes::Shape* shape = new shapes::Box(.1, .1, .1); + shapes::ShapeConstPtr shape_ptr(shape); + + Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity(); + pos1.translation().z() = 0.3; + c_env_->getWorld()->addToObject("box", shape_ptr, pos1); + + c_env_->checkSelfCollision(req, res, *robot_state_, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_TRUE(res.collision); + res.clear(); + + c_env_->getWorld()->moveObject("box", pos1); + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_TRUE(res.collision); + res.clear(); + + c_env_->getWorld()->moveObject("box", pos1); + ASSERT_FALSE(res.collision); +} + +/** \brief Adding obstacles to the world which are tested against the robot. */ +TEST_F(CollisionDetectionEnvTest, RobotWorldCollision_2) +{ + collision_detection::CollisionRequest req; + collision_detection::CollisionResult res; + req.max_contacts = 10; + req.contacts = true; + req.verbose = true; + + shapes::Shape* shape = new shapes::Box(.4, .4, .4); + shapes::ShapeConstPtr shape_ptr(shape); + + Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity(); + pos1.translation().z() = 0.3; + c_env_->getWorld()->addToObject("box", shape_ptr, pos1); + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_TRUE(res.collision); + ASSERT_GE(res.contact_count, 3u); + res.clear(); +} + +/** \brief Tests the padding through expanding the link geometry in such a way that a collision occurs. */ +TEST_F(CollisionDetectionEnvTest, PaddingTest) +{ + collision_detection::CollisionRequest req; + req.contacts = true; + req.max_contacts = 10; + collision_detection::CollisionResult res; + + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + // Adding the box right in front of the robot hand + shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1); + shapes::ShapeConstPtr shape_ptr(shape); + + Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() }; + pos.translation().x() = 0.43; + pos.translation().y() = 0; + pos.translation().z() = 0.55; + c_env_->getWorld()->addToObject("box", shape_ptr, pos); + + c_env_->setLinkPadding("panda_hand", 0.08); + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_TRUE(res.collision); + res.clear(); + + c_env_->setLinkPadding("panda_hand", 0.0); + c_env_->checkRobotCollision(req, res, *robot_state_, *acm_); + ASSERT_FALSE(res.collision); +} + +/** \brief Continuous self collision checks of the robot. + * + * Functionality not supported yet. */ +TEST_F(CollisionDetectionEnvTest, DISABLED_ContinuousCollisionSelf) +{ + collision_detection::CollisionRequest req; + collision_detection::CollisionResult res; + + robot_state::RobotState state1(robot_model_); + robot_state::RobotState state2(robot_model_); + + setToHome(state1); + double joint2 = 0.15; + double joint4 = -3.0; + double joint5 = -0.8; + double joint7 = -0.785; + state1.setJointPositions("panda_joint2", &joint2); + state1.setJointPositions("panda_joint4", &joint4); + state1.setJointPositions("panda_joint5", &joint5); + state1.setJointPositions("panda_joint7", &joint7); + state1.update(); + + c_env_->checkSelfCollision(req, res, state1, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + setToHome(state2); + double joint_5_other = 0.8; + state2.setJointPositions("panda_joint2", &joint2); + state2.setJointPositions("panda_joint4", &joint4); + state2.setJointPositions("panda_joint5", &joint_5_other); + state2.setJointPositions("panda_joint7", &joint7); + state2.update(); + + c_env_->checkSelfCollision(req, res, state2, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + // c_env_->checkSelfCollision(req, res, state1, state2, *acm_); + ROS_INFO_STREAM("Continous to continous collisions are not supported yet, therefore fail here."); + ASSERT_TRUE(res.collision); + res.clear(); +} + +/** \brief Two similar robot poses are used as start and end pose of a continuous collision check. + * + * Functionality not supported yet. */ +TEST_F(CollisionDetectionEnvTest, DISABLED_ContinuousCollisionWorld) +{ + collision_detection::CollisionRequest req; + req.contacts = true; + req.max_contacts = 10; + collision_detection::CollisionResult res; + + robot_state::RobotState state1(robot_model_); + robot_state::RobotState state2(robot_model_); + + setToHome(state1); + state1.update(); + + setToHome(state2); + double joint_2{ 0.05 }; + double joint_4{ -1.6 }; + state2.setJointPositions("panda_joint2", &joint_2); + state2.setJointPositions("panda_joint4", &joint_4); + state2.update(); + + c_env_->checkRobotCollision(req, res, state1, state2, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + // Adding the box which is not in collision with the individual states but sits right between them. + shapes::Shape* shape = new shapes::Box(0.1, 0.1, 0.1); + shapes::ShapeConstPtr shape_ptr(shape); + + Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() }; + pos.translation().x() = 0.43; + pos.translation().y() = 0; + pos.translation().z() = 0.55; + c_env_->getWorld()->addToObject("box", shape_ptr, pos); + + c_env_->checkRobotCollision(req, res, state1, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + c_env_->checkRobotCollision(req, res, state2, *acm_); + ASSERT_FALSE(res.collision); + res.clear(); + + c_env_->checkRobotCollision(req, res, state1, state2, *acm_); + ASSERT_TRUE(res.collision); + ASSERT_EQ(res.contact_count, 4u); + res.clear(); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/moveit_core/collision_distance_field/CMakeLists.txt b/moveit_core/collision_distance_field/CMakeLists.txt index ad1850a61e..063a1331a3 100644 --- a/moveit_core/collision_distance_field/CMakeLists.txt +++ b/moveit_core/collision_distance_field/CMakeLists.txt @@ -8,10 +8,8 @@ endif() add_library(${MOVEIT_LIB_NAME} src/collision_distance_field_types.cpp src/collision_common_distance_field.cpp - src/collision_robot_distance_field.cpp - src/collision_world_distance_field.cpp - src/collision_robot_hybrid.cpp - src/collision_world_hybrid.cpp + src/collision_env_distance_field.cpp + src/collision_env_hybrid.cpp ) set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") target_link_libraries(${MOVEIT_LIB_NAME} diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h index 024be61cfe..cfb6fe750d 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_common_distance_field.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include namespace collision_detection diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h index 9581cefa7b..b699170892 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_distance_field.h @@ -37,17 +37,15 @@ #pragma once #include -#include -#include +#include namespace collision_detection { /** \brief An allocator for Distance Field collision detectors */ class CollisionDetectorAllocatorDistanceField - : public CollisionDetectorAllocatorTemplate + : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_world_distance_field.cpp + static const std::string NAME; // defined in collision_env_distance_field.cpp }; } diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h index a2c643b282..efce4d7b11 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_detector_allocator_hybrid.h @@ -37,17 +37,15 @@ #pragma once #include -#include -#include +#include namespace collision_detection { /** \brief An allocator for Hybrid collision detectors */ class CollisionDetectorAllocatorHybrid - : public CollisionDetectorAllocatorTemplate + : public CollisionDetectorAllocatorTemplate { public: - static const std::string NAME; // defined in collision_world_hybrid.cpp + static const std::string NAME; // defined in collision_env_hybrid.cpp }; } diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h similarity index 57% rename from moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h rename to moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index dd13b12043..f9fb4366ad 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -37,9 +37,9 @@ #pragma once #include -#include #include #include +#include #include #include @@ -53,32 +53,36 @@ static const double DEFAULT_RESOLUTION = .02; static const double DEFAULT_COLLISION_TOLERANCE = 0.0; static const double DEFAULT_MAX_PROPOGATION_DISTANCE = .25; -MOVEIT_CLASS_FORWARD(CollisionRobotDistanceField); +MOVEIT_CLASS_FORWARD(CollisionEnvDistanceField); -class CollisionRobotDistanceField : public CollisionRobot +class CollisionEnvDistanceField : public CollisionEnv { - friend class CollisionWorldDistanceField; - public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - CollisionRobotDistanceField(const robot_model::RobotModelConstPtr& robot_model); - - CollisionRobotDistanceField(const CollisionRobot& col_robot, const Eigen::Vector3d& size, - const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, - double collision_tolerance, double max_propogation_distance, double padding); - - CollisionRobotDistanceField(const robot_model::RobotModelConstPtr& robot_model, - const std::map>& link_body_decompositions, - double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, - double size_z = DEFAULT_SIZE_Z, - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, - double resolution = DEFAULT_RESOLUTION, - double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, - double scale = 1.0); - - CollisionRobotDistanceField(const CollisionRobotDistanceField& other); + CollisionEnvDistanceField(const robot_model::RobotModelConstPtr& robot_model, + const std::map>& link_body_decompositions = + std::map>(), + double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, + double size_z = DEFAULT_SIZE_Z, Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, + double resolution = DEFAULT_RESOLUTION, + double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, + double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, + double scale = 1.0); + + CollisionEnvDistanceField(const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, + const std::map>& link_body_decompositions = + std::map>(), + double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, + double size_z = DEFAULT_SIZE_Z, Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, + double resolution = DEFAULT_RESOLUTION, + double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, + double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, + double scale = 1.0); + + CollisionEnvDistanceField(const CollisionEnvDistanceField& other, const WorldPtr& world); void initialize(const std::map>& link_body_decompositions, const Eigen::Vector3d& size, const Eigen::Vector3d& origin, bool use_signed_distance_field, @@ -98,51 +102,6 @@ class CollisionRobotDistanceField : public CollisionRobot const moveit::core::RobotState& state, const collision_detection::AllowedCollisionMatrix& acm, GroupStateRepresentationPtr& gsr) const; - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state1, const moveit::core::RobotState& state2) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - - void checkSelfCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state1, const moveit::core::RobotState& state2, - const collision_detection::AllowedCollisionMatrix& acm) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - - void checkOtherCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, const CollisionRobot& other_robot, - const moveit::core::RobotState& other_state) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - - void checkOtherCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, const CollisionRobot& other_robot, - const moveit::core::RobotState& other_state, - const collision_detection::AllowedCollisionMatrix& acm) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - - void checkOtherCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state1, const moveit::core::RobotState& state2, - const CollisionRobot& other_robot, const moveit::core::RobotState& other_state1, - const moveit::core::RobotState& other_state2) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - - void checkOtherCollision(const collision_detection::CollisionRequest& req, collision_detection::CollisionResult& res, - const moveit::core::RobotState& state1, const moveit::core::RobotState& state2, - const CollisionRobot& other_robot, const moveit::core::RobotState& other_state1, - const moveit::core::RobotState& other_state2, - const collision_detection::AllowedCollisionMatrix& acm) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - }; - void createCollisionModelMarker(const moveit::core::RobotState& state, visualization_msgs::MarkerArray& model_markers) const; @@ -150,22 +109,12 @@ class CollisionRobotDistanceField : public CollisionRobot { return 0.0; }; + virtual double distanceSelf(const moveit::core::RobotState& state, const collision_detection::AllowedCollisionMatrix& acm) const { return 0.0; }; - virtual double distanceOther(const moveit::core::RobotState& state, const CollisionRobot& other_robot, - const moveit::core::RobotState& other_state) const - { - return 0.0; - }; - virtual double distanceOther(const moveit::core::RobotState& state, const CollisionRobot& other_robot, - const moveit::core::RobotState& other_state, - const collision_detection::AllowedCollisionMatrix& acm) const - { - return 0.0; - }; void distanceSelf(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state) const override @@ -173,12 +122,6 @@ class CollisionRobotDistanceField : public CollisionRobot ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); } - void distanceOther(const DistanceRequest& req, DistanceResult& res, const robot_state::RobotState& state, - const CollisionRobot& other_robot, const robot_state::RobotState& other_state) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - } - DistanceFieldCacheEntryConstPtr getLastDistanceFieldEntry() const { return distance_field_cache_entry_; @@ -191,6 +134,84 @@ class CollisionRobotDistanceField : public CollisionRobot // const // collision_detection::AllowedCollisionMatrix // &acm) const; + + MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntryWorld) + struct DistanceFieldCacheEntryWorld + { + std::map> posed_body_point_decompositions_; + distance_field::DistanceFieldPtr distance_field_; + }; + + ~CollisionEnvDistanceField() override; + + void checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const override; + + virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const; + + void checkCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm, GroupStateRepresentationPtr& gsr) const; + + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; + + void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, const robot_state::RobotState& state2, + const AllowedCollisionMatrix& acm) const override; + + virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const override; + + virtual double distanceRobot(const robot_state::RobotState& state, bool verbose = false) const + { + return 0.0; + } + + virtual double distanceRobot(const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + bool verbose = false) const + { + return 0.0; + } + + void distanceRobot(const DistanceRequest& req, DistanceResult& res, + const robot_state::RobotState& state) const override + { + ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); + } + + void setWorld(const WorldPtr& world) override; + + distance_field::DistanceFieldConstPtr getDistanceField() const + { + return distance_field_cache_entry_->distance_field_; + } + + collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const + { + return last_gsr_; + } + + void getCollisionGradients(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const; + + void getAllCollisions(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const; + protected: bool getSelfProximityGradients(GroupStateRepresentationPtr& gsr) const; @@ -244,6 +265,20 @@ class CollisionRobotDistanceField : public CollisionRobot void updatedPaddingOrScaling(const std::vector& links) override{}; + DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld(); + + void updateDistanceObject(const std::string& id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr& dfce, + EigenSTL::vector_Vector3d& add_points, EigenSTL::vector_Vector3d& subtract_points); + + bool getEnvironmentCollisions(const CollisionRequest& req, CollisionResult& res, + const distance_field::DistanceFieldConstPtr& env_distance_field, + GroupStateRepresentationPtr& gsr) const; + + bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr& env_distance_field, + GroupStateRepresentationPtr& gsr) const; + + static void notifyObjectChange(CollisionEnvDistanceField* self, const ObjectConstPtr& obj, World::Action action); + Eigen::Vector3d size_; Eigen::Vector3d origin_; bool use_signed_distance_field_; @@ -260,5 +295,10 @@ class CollisionRobotDistanceField : public CollisionRobot std::map pregenerated_group_state_representation_map_; planning_scene::PlanningScenePtr planning_scene_; + + mutable boost::mutex update_cache_lock_world_; + DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_; + GroupStateRepresentationPtr last_gsr_; + World::ObserverHandle observer_handle_; }; } diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h new file mode 100644 index 0000000000..784623385d --- /dev/null +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -0,0 +1,153 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: E. Gil Jones, Jens Petit */ + +#pragma once + +#include +#include +#include +#include + +#include + +namespace collision_detection +{ +/** \brief This hybrid collision environment combines FCL and a distance field. Both can be used to calculate + * collisions. */ +class CollisionEnvHybrid : public collision_detection::CollisionEnvFCL +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + CollisionEnvHybrid(const robot_model::RobotModelConstPtr& robot_model, + const std::map>& link_body_decompositions = + std::map>(), + double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z, + Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, + double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, + double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, + double scale = 1.0); + + CollisionEnvHybrid(const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, + const std::map>& link_body_decompositions = + std::map>(), + double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z, + Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, + double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, + double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, + double scale = 1.0); + + CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world); + + ~CollisionEnvHybrid() override + { + } + + void initializeRobotDistanceField(const std::map>& link_body_decompositions, + double size_x, double size_y, double size_z, bool use_signed_distance_field, + double resolution, double collision_tolerance, double max_propogation_distance) + { + cenv_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), + Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance, + max_propogation_distance); + } + + void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const robot_state::RobotState& state) const; + + void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const; + + void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, const robot_state::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm) const; + + void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, const robot_state::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const; + const CollisionEnvDistanceFieldConstPtr getCollisionRobotDistanceField() const + { + return cenv_distance_; + } + + void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const; + + void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; + + void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; + + void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const; + + void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const; + + void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; + + void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; + + void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const; + + void setWorld(const WorldPtr& world) override; + + void getCollisionGradients(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const; + + void getAllCollisions(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const; + + const CollisionEnvDistanceFieldConstPtr getCollisionWorldDistanceField() const + { + return cenv_distance_; + } + +protected: + CollisionEnvDistanceFieldPtr cenv_distance_; +}; +}; diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h deleted file mode 100644 index 7b188ce97e..0000000000 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_robot_hybrid.h +++ /dev/null @@ -1,98 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#pragma once - -#include -#include -#include -#include - -#include - -namespace collision_detection -{ -class CollisionRobotHybrid : public collision_detection::CollisionRobotFCL -{ -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - CollisionRobotHybrid(const robot_model::RobotModelConstPtr& robot_model); - - CollisionRobotHybrid(const robot_model::RobotModelConstPtr& robot_model, - const std::map>& link_body_decompositions, - double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z, - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, - double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, - double scale = 1.0); - - CollisionRobotHybrid(const CollisionRobotHybrid& other); - - void initializeRobotDistanceField(const std::map>& link_body_decompositions, - double size_x, double size_y, double size_z, bool use_signed_distance_field, - double resolution, double collision_tolerance, double max_propogation_distance) - { - crobot_distance_->initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), - Eigen::Vector3d(0, 0, 0), use_signed_distance_field, resolution, collision_tolerance, - max_propogation_distance); - } - - void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const robot_state::RobotState& state) const; - - void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const; - - void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, const robot_state::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm) const; - - void checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, const robot_state::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const; - const CollisionRobotDistanceFieldConstPtr getCollisionRobotDistanceField() const - { - return crobot_distance_; - } - -protected: - CollisionRobotDistanceFieldPtr crobot_distance_; -}; -} diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h deleted file mode 100644 index ff05802ab9..0000000000 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_distance_field.h +++ /dev/null @@ -1,200 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#pragma once - -#include -#include -#include -#include - -namespace collision_detection -{ -MOVEIT_CLASS_FORWARD(CollisionWorldDistanceField) - -class CollisionWorldDistanceField : public CollisionWorld -{ -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - MOVEIT_STRUCT_FORWARD(DistanceFieldCacheEntry) - struct DistanceFieldCacheEntry - { - std::map> posed_body_point_decompositions_; - distance_field::DistanceFieldPtr distance_field_; - }; - - CollisionWorldDistanceField(Eigen::Vector3d size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, - double resolution = DEFAULT_RESOLUTION, - double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE); - - explicit CollisionWorldDistanceField( - const WorldPtr& world, Eigen::Vector3d size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution = DEFAULT_RESOLUTION, - double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE); - - CollisionWorldDistanceField(const CollisionWorldDistanceField& other, const WorldPtr& world); - - ~CollisionWorldDistanceField() override; - - void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const override; - - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; - - void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const override; - - virtual void checkCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const; - - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const override; - - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; - - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const override; - - virtual void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const; - - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2) const override - { - } - void checkRobotCollision(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state1, const robot_state::RobotState& state2, - const AllowedCollisionMatrix& acm) const override - { - } - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionWorld& other_world) const override - { - } - void checkWorldCollision(const CollisionRequest& req, CollisionResult& res, const CollisionWorld& other_world, - const AllowedCollisionMatrix& acm) const override - { - } - - virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state, - bool verbose = false) const - { - return 0.0; - } - virtual double distanceRobot(const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, bool verbose = false) const - { - return 0.0; - } - virtual double distanceWorld(const CollisionWorld& world, bool verbose = false) const - { - return 0.0; - } - virtual double distanceWorld(const CollisionWorld& world, const AllowedCollisionMatrix& acm, - bool verbose = false) const - { - return 0.0; - } - - void distanceRobot(const DistanceRequest& req, DistanceResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - } - - void distanceWorld(const DistanceRequest& req, DistanceResult& res, const CollisionWorld& world) const override - { - ROS_ERROR_NAMED("collision_distance_field", "Not implemented"); - } - - void setWorld(const WorldPtr& world) override; - - distance_field::DistanceFieldConstPtr getDistanceField() const - { - return distance_field_cache_entry_->distance_field_; - } - - collision_detection::GroupStateRepresentationConstPtr getLastGroupStateRepresentation() const - { - return last_gsr_; - } - - void getCollisionGradients(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const; - - void getAllCollisions(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const; - -protected: - DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(); - - void updateDistanceObject(const std::string& id, CollisionWorldDistanceField::DistanceFieldCacheEntryPtr& dfce, - EigenSTL::vector_Vector3d& add_points, EigenSTL::vector_Vector3d& subtract_points); - - bool getEnvironmentCollisions(const CollisionRequest& req, CollisionResult& res, - const distance_field::DistanceFieldConstPtr& env_distance_field, - GroupStateRepresentationPtr& gsr) const; - - bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr& env_distance_field, - GroupStateRepresentationPtr& gsr) const; - - static void notifyObjectChange(CollisionWorldDistanceField* self, const ObjectConstPtr& obj, World::Action action); - - Eigen::Vector3d size_; - Eigen::Vector3d origin_; - bool use_signed_distance_field_; - double resolution_; - double collision_tolerance_; - double max_propogation_distance_; - - mutable boost::mutex update_cache_lock_; - DistanceFieldCacheEntryPtr distance_field_cache_entry_; - GroupStateRepresentationPtr last_gsr_; - World::ObserverHandle observer_handle_; -}; -} diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h deleted file mode 100644 index bb3d07e8cf..0000000000 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_world_hybrid.h +++ /dev/null @@ -1,116 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#pragma once - -#include -#include -#include -#include - -namespace collision_detection -{ -class CollisionRobotHybrid; - -class CollisionWorldHybrid : public CollisionWorldFCL -{ -public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - CollisionWorldHybrid(Eigen::Vector3d size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, - double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE); - - explicit CollisionWorldHybrid(const WorldPtr& world, - Eigen::Vector3d size = Eigen::Vector3d(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z), - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), - bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, - double resolution = DEFAULT_RESOLUTION, - double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, - double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE); - - CollisionWorldHybrid(const CollisionWorldHybrid& other, const WorldPtr& world); - - ~CollisionWorldHybrid() override - { - } - - void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const; - - void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; - - void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; - - void checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const; - - void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state) const; - - void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, GroupStateRepresentationPtr& gsr) const; - - void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm) const; - - void checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const; - - void setWorld(const WorldPtr& world) override; - - void getCollisionGradients(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const; - - void getAllCollisions(const CollisionRequest& req, CollisionResult& res, const CollisionRobot& robot, - const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const; - - const CollisionWorldDistanceFieldConstPtr getCollisionWorldDistanceField() const - { - return cworld_distance_; - } - -protected: - CollisionWorldDistanceFieldPtr cworld_distance_; -}; -} diff --git a/moveit_core/collision_distance_field/src/collision_robot_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp similarity index 68% rename from moveit_core/collision_distance_field/src/collision_robot_distance_field.cpp rename to moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index 85cf2246ee..0c1cc66d9f 100644 --- a/moveit_core/collision_distance_field/src/collision_robot_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -35,54 +35,61 @@ /* Author: E. Gil Jones */ #include -#include -#include -#include #include #include #include +#include +#include +#include +#include +#include +#include +#include namespace collision_detection { const double EPSILON = 0.001f; -CollisionRobotDistanceField::CollisionRobotDistanceField(const robot_model::RobotModelConstPtr& robot_model) - : CollisionRobot(robot_model) +const std::string collision_detection::CollisionDetectorAllocatorDistanceField::NAME("DISTANCE_FIELD"); + +CollisionEnvDistanceField::CollisionEnvDistanceField( + const robot_model::RobotModelConstPtr& robot_model, + const std::map>& link_body_decompositions, double size_x, double size_y, + double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double collision_tolerance, double max_propogation_distance, double padding, double scale) + : CollisionEnv(robot_model) { - // planning_scene_.reset(new planning_scene::PlanningScene(robot_model_)); + initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field, + resolution, collision_tolerance, max_propogation_distance); - std::map> link_body_decompositions; - Eigen::Vector3d size(DEFAULT_SIZE_X, DEFAULT_SIZE_Y, DEFAULT_SIZE_Z); - initialize(link_body_decompositions, size, Eigen::Vector3d(0, 0, 0), DEFAULT_USE_SIGNED_DISTANCE_FIELD, - DEFAULT_RESOLUTION, DEFAULT_COLLISION_TOLERANCE, DEFAULT_MAX_PROPOGATION_DISTANCE); setPadding(0.0); + + distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld(); + + // request notifications about changes to world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2)); } -CollisionRobotDistanceField::CollisionRobotDistanceField( - const robot_model::RobotModelConstPtr& robot_model, +CollisionEnvDistanceField::CollisionEnvDistanceField( + const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, - double max_propogation_distance, double padding, double scale) - : CollisionRobot(robot_model, padding, scale) + double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double collision_tolerance, double max_propogation_distance, double padding, double scale) + : CollisionEnv(robot_model, world, padding, scale) { - initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), Eigen::Vector3d(0, 0, 0), - use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance); -} + initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field, + resolution, collision_tolerance, max_propogation_distance); -CollisionRobotDistanceField::CollisionRobotDistanceField(const CollisionRobot& col_robot, const Eigen::Vector3d& size, - const Eigen::Vector3d& origin, bool use_signed_distance_field, - double resolution, double collision_tolerance, - double max_propogation_distance, double padding) - : CollisionRobot(col_robot) -{ - std::map> link_body_decompositions; - initialize(link_body_decompositions, size, origin, use_signed_distance_field, resolution, collision_tolerance, - max_propogation_distance); - setPadding(padding); + distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld(); + + // request notifications about changes to world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2)); + + getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); } -CollisionRobotDistanceField::CollisionRobotDistanceField(const CollisionRobotDistanceField& other) - : CollisionRobot(other) +CollisionEnvDistanceField::CollisionEnvDistanceField(const CollisionEnvDistanceField& other, const WorldPtr& world) + : CollisionEnv(other, world) { size_ = other.size_; origin_ = other.origin_; @@ -94,11 +101,21 @@ CollisionRobotDistanceField::CollisionRobotDistanceField(const CollisionRobotDis link_body_decomposition_vector_ = other.link_body_decomposition_vector_; link_body_decomposition_index_map_ = other.link_body_decomposition_index_map_; in_group_update_map_ = other.in_group_update_map_; + distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld(); pregenerated_group_state_representation_map_ = other.pregenerated_group_state_representation_map_; planning_scene_.reset(new planning_scene::PlanningScene(robot_model_)); + + // request notifications about changes to world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2)); + getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); +} + +CollisionEnvDistanceField::~CollisionEnvDistanceField() +{ + getWorld()->removeObserver(observer_handle_); } -void CollisionRobotDistanceField::initialize( +void CollisionEnvDistanceField::initialize( const std::map>& link_body_decompositions, const Eigen::Vector3d& size, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance) @@ -130,7 +147,7 @@ void CollisionRobotDistanceField::initialize( } } -void CollisionRobotDistanceField::generateCollisionCheckingStructures( +void CollisionEnvDistanceField::generateCollisionCheckingStructures( const std::string& group_name, const moveit::core::RobotState& state, const collision_detection::AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr, bool generate_distance_field) const @@ -143,17 +160,17 @@ void CollisionRobotDistanceField::generateCollisionCheckingStructures( DistanceFieldCacheEntryPtr new_dfce = generateDistanceFieldCacheEntry(group_name, state, acm, generate_distance_field); boost::mutex::scoped_lock slock(update_cache_lock_); - (const_cast(this))->distance_field_cache_entry_ = new_dfce; + (const_cast(this))->distance_field_cache_entry_ = new_dfce; dfce = new_dfce; } getGroupStateRepresentation(dfce, state, gsr); } -void CollisionRobotDistanceField::checkSelfCollisionHelper(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, - const collision_detection::AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const +void CollisionEnvDistanceField::checkSelfCollisionHelper(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& state, + const collision_detection::AllowedCollisionMatrix* acm, + GroupStateRepresentationPtr& gsr) const { if (!gsr) { @@ -174,9 +191,9 @@ void CollisionRobotDistanceField::checkSelfCollisionHelper(const collision_detec } DistanceFieldCacheEntryConstPtr -CollisionRobotDistanceField::getDistanceFieldCacheEntry(const std::string& group_name, - const moveit::core::RobotState& state, - const collision_detection::AllowedCollisionMatrix* acm) const +CollisionEnvDistanceField::getDistanceFieldCacheEntry(const std::string& group_name, + const moveit::core::RobotState& state, + const collision_detection::AllowedCollisionMatrix* acm) const { DistanceFieldCacheEntryConstPtr ret; if (!distance_field_cache_entry_) @@ -205,36 +222,36 @@ CollisionRobotDistanceField::getDistanceFieldCacheEntry(const std::string& group return cur; } -void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& state) const +void CollisionEnvDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& state) const { GroupStateRepresentationPtr gsr; checkSelfCollisionHelper(req, res, state, nullptr, gsr); } -void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, - GroupStateRepresentationPtr& gsr) const +void CollisionEnvDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& state, + GroupStateRepresentationPtr& gsr) const { checkSelfCollisionHelper(req, res, state, nullptr, gsr); } -void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm) const +void CollisionEnvDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm) const { GroupStateRepresentationPtr gsr; checkSelfCollisionHelper(req, res, state, &acm, gsr); } -void CollisionRobotDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const moveit::core::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const +void CollisionEnvDistanceField::checkSelfCollision(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const moveit::core::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const { if (gsr) { @@ -244,9 +261,9 @@ void CollisionRobotDistanceField::checkSelfCollision(const collision_detection:: checkSelfCollisionHelper(req, res, state, &acm, gsr); } -bool CollisionRobotDistanceField::getSelfCollisions(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - GroupStateRepresentationPtr& gsr) const +bool CollisionEnvDistanceField::getSelfCollisions(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + GroupStateRepresentationPtr& gsr) const { for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++) { @@ -324,7 +341,7 @@ bool CollisionRobotDistanceField::getSelfCollisions(const collision_detection::C return (res.contact_count >= req.max_contacts); } -bool CollisionRobotDistanceField::getSelfProximityGradients(GroupStateRepresentationPtr& gsr) const +bool CollisionEnvDistanceField::getSelfProximityGradients(GroupStateRepresentationPtr& gsr) const { bool in_collision = false; @@ -399,9 +416,9 @@ bool CollisionRobotDistanceField::getSelfProximityGradients(GroupStateRepresenta return in_collision; } -bool CollisionRobotDistanceField::getIntraGroupCollisions(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - GroupStateRepresentationPtr& gsr) const +bool CollisionEnvDistanceField::getIntraGroupCollisions(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + GroupStateRepresentationPtr& gsr) const { unsigned int num_links = gsr->dfce_->link_names_.size(); unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size(); @@ -628,7 +645,7 @@ bool CollisionRobotDistanceField::getIntraGroupCollisions(const collision_detect return false; } -bool CollisionRobotDistanceField::getIntraGroupProximityGradients(GroupStateRepresentationPtr& gsr) const +bool CollisionEnvDistanceField::getIntraGroupProximityGradients(GroupStateRepresentationPtr& gsr) const { bool in_collision = false; unsigned int num_links = gsr->dfce_->link_names_.size(); @@ -694,7 +711,7 @@ bool CollisionRobotDistanceField::getIntraGroupProximityGradients(GroupStateRepr } return in_collision; } -DistanceFieldCacheEntryPtr CollisionRobotDistanceField::generateDistanceFieldCacheEntry( +DistanceFieldCacheEntryPtr CollisionEnvDistanceField::generateDistanceFieldCacheEntry( const std::string& group_name, const moveit::core::RobotState& state, const collision_detection::AllowedCollisionMatrix* acm, bool generate_distance_field) const { @@ -947,7 +964,7 @@ DistanceFieldCacheEntryPtr CollisionRobotDistanceField::generateDistanceFieldCac return dfce; } -void CollisionRobotDistanceField::addLinkBodyDecompositions(double resolution) +void CollisionEnvDistanceField::addLinkBodyDecompositions(double resolution) { const std::vector& link_models = robot_model_->getLinkModelsWithCollisionGeometry(); for (const moveit::core::LinkModel* link_model : link_models) @@ -967,8 +984,8 @@ void CollisionRobotDistanceField::addLinkBodyDecompositions(double resolution) } } -void CollisionRobotDistanceField::createCollisionModelMarker(const moveit::core::RobotState& state, - visualization_msgs::MarkerArray& model_markers) const +void CollisionEnvDistanceField::createCollisionModelMarker(const moveit::core::RobotState& state, + visualization_msgs::MarkerArray& model_markers) const { // creating colors std_msgs::ColorRGBA robot_color; @@ -1035,7 +1052,7 @@ void CollisionRobotDistanceField::createCollisionModelMarker(const moveit::core: } } -void CollisionRobotDistanceField::addLinkBodyDecompositions( +void CollisionEnvDistanceField::addLinkBodyDecompositions( double resolution, const std::map>& link_spheres) { ROS_ASSERT_MSG(robot_model_, "RobotModelPtr is invalid"); @@ -1065,7 +1082,7 @@ void CollisionRobotDistanceField::addLinkBodyDecompositions( ROS_DEBUG_STREAM(__FUNCTION__ << " Finished "); } -PosedBodySphereDecompositionPtr CollisionRobotDistanceField::getPosedLinkBodySphereDecomposition( +PosedBodySphereDecompositionPtr CollisionEnvDistanceField::getPosedLinkBodySphereDecomposition( const moveit::core::LinkModel* ls, unsigned int ind) const { PosedBodySphereDecompositionPtr ret; @@ -1074,7 +1091,7 @@ PosedBodySphereDecompositionPtr CollisionRobotDistanceField::getPosedLinkBodySph } PosedBodyPointDecompositionPtr -CollisionRobotDistanceField::getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel* ls) const +CollisionEnvDistanceField::getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel* ls) const { PosedBodyPointDecompositionPtr ret; std::map::const_iterator it = link_body_decomposition_index_map_.find(ls->getName()); @@ -1087,8 +1104,8 @@ CollisionRobotDistanceField::getPosedLinkBodyPointDecomposition(const moveit::co return ret; } -void CollisionRobotDistanceField::updateGroupStateRepresentationState(const moveit::core::RobotState& state, - GroupStateRepresentationPtr& gsr) const +void CollisionEnvDistanceField::updateGroupStateRepresentationState(const moveit::core::RobotState& state, + GroupStateRepresentationPtr& gsr) const { for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++) { @@ -1141,9 +1158,9 @@ void CollisionRobotDistanceField::updateGroupStateRepresentationState(const move } } -void CollisionRobotDistanceField::getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr& dfce, - const moveit::core::RobotState& state, - GroupStateRepresentationPtr& gsr) const +void CollisionEnvDistanceField::getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr& dfce, + const moveit::core::RobotState& state, + GroupStateRepresentationPtr& gsr) const { if (!dfce->pregenerated_group_state_representation_) { @@ -1239,8 +1256,8 @@ void CollisionRobotDistanceField::getGroupStateRepresentation(const DistanceFiel } } -bool CollisionRobotDistanceField::compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr& dfce, - const moveit::core::RobotState& state) const +bool CollisionEnvDistanceField::compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr& dfce, + const moveit::core::RobotState& state) const { std::vector new_state_values(state.getVariableCount()); for (unsigned int i = 0; i < new_state_values.size(); i++) @@ -1299,7 +1316,7 @@ bool CollisionRobotDistanceField::compareCacheEntryToState(const DistanceFieldCa return true; } -bool CollisionRobotDistanceField::compareCacheEntryToAllowedCollisionMatrix( +bool CollisionEnvDistanceField::compareCacheEntryToAllowedCollisionMatrix( const DistanceFieldCacheEntryConstPtr& dfce, const collision_detection::AllowedCollisionMatrix& acm) const { if (dfce->acm_.getSize() != acm.getSize()) @@ -1361,7 +1378,7 @@ bool CollisionRobotDistanceField::compareCacheEntryToAllowedCollisionMatrix( } // void -// CollisionRobotDistanceField::generateAllowedCollisionInformation(CollisionRobotDistanceField::DistanceFieldCacheEntryPtr& +// CollisionEnvDistanceField::generateAllowedCollisionInformation(CollisionEnvDistanceField::DistanceFieldCacheEntryPtr& // dfce) // { // for(unsigned int i = 0; i < dfce.link_names_.size(); i++) { @@ -1369,4 +1386,420 @@ bool CollisionRobotDistanceField::compareCacheEntryToAllowedCollisionMatrix( // if(dfce->acm.find // } // } + +void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + GroupStateRepresentationPtr gsr; + checkCollision(req, res, state, gsr); +} + +void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const +{ + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, true); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + bool done = getSelfCollisions(req, res, gsr); + if (!done) + { + done = getIntraGroupCollisions(req, res, gsr); + } + if (!done) + { + getEnvironmentCollisions(req, res, distance_field_cache_entry_world_->distance_field_, gsr); + } + + (const_cast(this))->last_gsr_ = gsr; +} + +void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const +{ + GroupStateRepresentationPtr gsr; + checkCollision(req, res, state, acm, gsr); +} + +void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const +{ + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + bool done = getSelfCollisions(req, res, gsr); + if (!done) + { + done = getIntraGroupCollisions(req, res, gsr); + } + if (!done) + { + getEnvironmentCollisions(req, res, distance_field_cache_entry_world_->distance_field_, gsr); + } + + (const_cast(this))->last_gsr_ = gsr; +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + GroupStateRepresentationPtr gsr; + checkRobotCollision(req, res, state, gsr); +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const +{ + distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_; + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, false); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + getEnvironmentCollisions(req, res, env_distance_field, gsr); + (const_cast(this))->last_gsr_ = gsr; + + // checkRobotCollisionHelper(req, res, robot, state, &acm); +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const +{ + GroupStateRepresentationPtr gsr; + checkRobotCollision(req, res, state, acm, gsr); +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const +{ + distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_; + + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + getEnvironmentCollisions(req, res, env_distance_field, gsr); + (const_cast(this))->last_gsr_ = gsr; + + // checkRobotCollisionHelper(req, res, robot, state, &acm); +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2, + const AllowedCollisionMatrix& acm) const +{ + ROS_ERROR_NAMED("collision_detection.distance", "Continuous collision checking not implemented"); +} + +void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state1, + const robot_state::RobotState& state2) const +{ + ROS_ERROR_NAMED("collision_detection.distance", "Continuous collision checking not implemented"); +} + +void CollisionEnvDistanceField::getCollisionGradients(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, + GroupStateRepresentationPtr& gsr) const +{ + distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_; + + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + + getSelfProximityGradients(gsr); + getIntraGroupProximityGradients(gsr); + getEnvironmentProximityGradients(env_distance_field, gsr); + + (const_cast(this))->last_gsr_ = gsr; +} + +void CollisionEnvDistanceField::getAllCollisions(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix* acm, + GroupStateRepresentationPtr& gsr) const +{ + if (!gsr) + { + generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true); + } + else + { + updateGroupStateRepresentationState(state, gsr); + } + getSelfCollisions(req, res, gsr); + getIntraGroupCollisions(req, res, gsr); + distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_; + getEnvironmentCollisions(req, res, env_distance_field, gsr); + + (const_cast(this))->last_gsr_ = gsr; +} + +bool CollisionEnvDistanceField::getEnvironmentCollisions( + const CollisionRequest& req, CollisionResult& res, const distance_field::DistanceFieldConstPtr& env_distance_field, + GroupStateRepresentationPtr& gsr) const +{ + for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++) + { + bool is_link = i < gsr->dfce_->link_names_.size(); + std::string link_name = i < gsr->dfce_->link_names_.size() ? gsr->dfce_->link_names_[i] : "attached"; + if (is_link && !gsr->dfce_->link_has_geometry_[i]) + { + continue; + } + + const std::vector* collision_spheres_1; + const EigenSTL::vector_Vector3d* sphere_centers_1; + + if (is_link) + { + collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres()); + sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters()); + } + else + { + collision_spheres_1 = + &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres()); + sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()); + } + + if (req.contacts) + { + std::vector colls; + bool coll = getCollisionSphereCollision( + env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, max_propogation_distance_, + collision_tolerance_, std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls); + if (coll) + { + res.collision = true; + for (unsigned int col : colls) + { + Contact con; + if (is_link) + { + con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col]; + con.body_type_1 = BodyTypes::ROBOT_LINK; + con.body_name_1 = gsr->dfce_->link_names_[i]; + } + else + { + con.pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col]; + con.body_type_1 = BodyTypes::ROBOT_ATTACHED; + con.body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()]; + } + + con.body_type_2 = BodyTypes::WORLD_OBJECT; + con.body_name_2 = "environment"; + res.contact_count++; + res.contacts[std::pair(con.body_name_1, con.body_name_2)].push_back(con); + gsr->gradients_[i].types[col] = ENVIRONMENT; + // ROS_DEBUG_STREAM("Link " << dfce->link_names_[i] << " sphere " << + // colls[j] << " in env collision"); + } + + gsr->gradients_[i].collision = true; + if (res.contact_count >= req.max_contacts) + { + return true; + } + } + } + else + { + bool coll = getCollisionSphereCollision(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, + max_propogation_distance_, collision_tolerance_); + if (coll) + { + res.collision = true; + return true; + } + } + } + return (res.contact_count >= req.max_contacts); +} + +bool CollisionEnvDistanceField::getEnvironmentProximityGradients( + const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr) const +{ + bool in_collision = false; + for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++) + { + bool is_link = i < gsr->dfce_->link_names_.size(); + + if (is_link && !gsr->dfce_->link_has_geometry_[i]) + { + continue; + } + + const std::vector* collision_spheres_1; + const EigenSTL::vector_Vector3d* sphere_centers_1; + if (is_link) + { + collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres()); + sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters()); + } + else + { + collision_spheres_1 = + &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres()); + sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()); + } + + bool coll = getCollisionSphereGradients(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, + gsr->gradients_[i], ENVIRONMENT, collision_tolerance_, false, + max_propogation_distance_, false); + if (coll) + { + in_collision = true; + } + } + return in_collision; +} + +void CollisionEnvDistanceField::setWorld(const WorldPtr& world) +{ + if (world == getWorld()) + return; + + // turn off notifications about old world + getWorld()->removeObserver(observer_handle_); + + // clear out objects from old world + distance_field_cache_entry_world_->distance_field_->reset(); + + CollisionEnv::setWorld(world); + + // request notifications about changes to new world + observer_handle_ = getWorld()->addObserver(boost::bind(&CollisionEnvDistanceField::notifyObjectChange, this, _1, _2)); + + // get notifications any objects already in the new world + getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); +} + +void CollisionEnvDistanceField::notifyObjectChange(CollisionEnvDistanceField* self, const ObjectConstPtr& obj, + World::Action action) +{ + ros::WallTime n = ros::WallTime::now(); + + EigenSTL::vector_Vector3d add_points; + EigenSTL::vector_Vector3d subtract_points; + self->updateDistanceObject(obj->id_, self->distance_field_cache_entry_world_, add_points, subtract_points); + + if (action == World::DESTROY) + { + self->distance_field_cache_entry_world_->distance_field_->removePointsFromField(subtract_points); + } + else if (action & (World::MOVE_SHAPE | World::REMOVE_SHAPE)) + { + self->distance_field_cache_entry_world_->distance_field_->removePointsFromField(subtract_points); + self->distance_field_cache_entry_world_->distance_field_->addPointsToField(add_points); + } + else + { + self->distance_field_cache_entry_world_->distance_field_->addPointsToField(add_points); + } + + ROS_DEBUG_NAMED("collision_distance_field", "Modifying object %s took %lf s", obj->id_.c_str(), + (ros::WallTime::now() - n).toSec()); +} + +void CollisionEnvDistanceField::updateDistanceObject(const std::string& id, DistanceFieldCacheEntryWorldPtr& dfce, + EigenSTL::vector_Vector3d& add_points, + EigenSTL::vector_Vector3d& subtract_points) +{ + std::map>::iterator cur_it = + dfce->posed_body_point_decompositions_.find(id); + if (cur_it != dfce->posed_body_point_decompositions_.end()) + { + for (collision_detection::PosedBodyPointDecompositionPtr& posed_body_point_decomposition : cur_it->second) + { + subtract_points.insert(subtract_points.end(), posed_body_point_decomposition->getCollisionPoints().begin(), + posed_body_point_decomposition->getCollisionPoints().end()); + } + } + + World::ObjectConstPtr object = getWorld()->getObject(id); + if (object) + { + ROS_DEBUG_STREAM("Updating/Adding Object '" << object->id_ << "' with " << object->shapes_.size() + << " shapes to CollisionEnvDistanceField"); + std::vector shape_points; + for (unsigned int i = 0; i < object->shapes_.size(); i++) + { + shapes::ShapeConstPtr shape = object->shapes_[i]; + if (shape->type == shapes::OCTREE) + { + const shapes::OcTree* octree_shape = static_cast(shape.get()); + std::shared_ptr octree = octree_shape->octree; + + shape_points.push_back(std::make_shared(octree)); + } + else + { + BodyDecompositionConstPtr bd = getBodyDecompositionCacheEntry(shape, resolution_); + + shape_points.push_back(std::make_shared(bd, object->shape_poses_[i])); + } + + add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(), + shape_points.back()->getCollisionPoints().end()); + } + + dfce->posed_body_point_decompositions_[id] = shape_points; + } + else + { + ROS_DEBUG_STREAM("Removing Object '" << id << "' from CollisionEnvDistanceField"); + dfce->posed_body_point_decompositions_.erase(id); + } +} + +CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr +CollisionEnvDistanceField::generateDistanceFieldCacheEntryWorld() +{ + DistanceFieldCacheEntryWorldPtr dfce(new DistanceFieldCacheEntryWorld()); + dfce->distance_field_.reset(new distance_field::PropagationDistanceField( + size_.x(), size_.y(), size_.z(), resolution_, origin_.x() - 0.5 * size_.x(), origin_.y() - 0.5 * size_.y(), + origin_.z() - 0.5 * size_.z(), max_propogation_distance_, use_signed_distance_field_)); + + EigenSTL::vector_Vector3d add_points; + EigenSTL::vector_Vector3d subtract_points; + for (const std::pair& object : *getWorld()) + { + updateDistanceObject(object.first, dfce, add_points, subtract_points); + } + dfce->distance_field_->addPointsToField(add_points); + return dfce; +} } // namespace collision_detection diff --git a/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp new file mode 100644 index 0000000000..9c7928112d --- /dev/null +++ b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp @@ -0,0 +1,185 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: E. Gil Jones, Jens Petit */ + +#include +#include +#include + +namespace collision_detection +{ +const std::string collision_detection::CollisionDetectorAllocatorHybrid::NAME("HYBRID"); + +CollisionEnvHybrid::CollisionEnvHybrid( + const robot_model::RobotModelConstPtr& robot_model, + const std::map>& link_body_decompositions, double size_x, double size_y, + double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double collision_tolerance, double max_propogation_distance, double padding, double scale) + : CollisionEnvFCL(robot_model) + , cenv_distance_(new collision_detection::CollisionEnvDistanceField( + robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, std::move(origin), + use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance, padding, scale)) +{ +} + +CollisionEnvHybrid::CollisionEnvHybrid( + const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, + const std::map>& link_body_decompositions, double size_x, double size_y, + double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double collision_tolerance, double max_propogation_distance, double padding, double scale) + : CollisionEnvFCL(robot_model, world, padding, scale) + , cenv_distance_(new collision_detection::CollisionEnvDistanceField( + robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, std::move(origin), + use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance, padding, scale)) +{ +} + +CollisionEnvHybrid::CollisionEnvHybrid(const CollisionEnvHybrid& other, const WorldPtr& world) + : CollisionEnvFCL(other, world) + , cenv_distance_(new collision_detection::CollisionEnvDistanceField(*other.getCollisionWorldDistanceField(), world)) +{ +} + +void CollisionEnvHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const robot_state::RobotState& state) const +{ + cenv_distance_->checkSelfCollision(req, res, state); +} + +void CollisionEnvHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkSelfCollision(req, res, state, gsr); +} + +void CollisionEnvHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const robot_state::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm) const +{ + cenv_distance_->checkSelfCollision(req, res, state, acm); +} + +void CollisionEnvHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, + collision_detection::CollisionResult& res, + const robot_state::RobotState& state, + const collision_detection::AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkSelfCollision(req, res, state, acm, gsr); +} + +void CollisionEnvHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + cenv_distance_->checkCollision(req, res, state); +} + +void CollisionEnvHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkCollision(req, res, state, gsr); +} + +void CollisionEnvHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const +{ + cenv_distance_->checkCollision(req, res, state, acm); +} + +void CollisionEnvHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkCollision(req, res, state, acm, gsr); +} + +void CollisionEnvHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state) const +{ + cenv_distance_->checkRobotCollision(req, res, state); +} + +void CollisionEnvHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkRobotCollision(req, res, state, gsr); +} + +void CollisionEnvHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm) const +{ + cenv_distance_->checkRobotCollision(req, res, state, acm); +} + +void CollisionEnvHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, + const AllowedCollisionMatrix& acm, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->checkRobotCollision(req, res, state, acm, gsr); +} + +void CollisionEnvHybrid::setWorld(const WorldPtr& world) +{ + if (world == getWorld()) + return; + + cenv_distance_->setWorld(world); + CollisionEnvFCL::setWorld(world); +} + +void CollisionEnvHybrid::getCollisionGradients(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->getCollisionGradients(req, res, state, acm, gsr); +} + +void CollisionEnvHybrid::getAllCollisions(const CollisionRequest& req, CollisionResult& res, + const robot_state::RobotState& state, const AllowedCollisionMatrix* acm, + GroupStateRepresentationPtr& gsr) const +{ + cenv_distance_->getAllCollisions(req, res, state, acm, gsr); +} +} // namespace collision_detection diff --git a/moveit_core/collision_distance_field/src/collision_robot_hybrid.cpp b/moveit_core/collision_distance_field/src/collision_robot_hybrid.cpp deleted file mode 100644 index 45f35aea88..0000000000 --- a/moveit_core/collision_distance_field/src/collision_robot_hybrid.cpp +++ /dev/null @@ -1,96 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#include - -namespace collision_detection -{ -CollisionRobotHybrid::CollisionRobotHybrid(const robot_model::RobotModelConstPtr& robot_model) - : CollisionRobotFCL(robot_model) -{ - crobot_distance_.reset(new collision_detection::CollisionRobotDistanceField(robot_model)); -} - -CollisionRobotHybrid::CollisionRobotHybrid( - const robot_model::RobotModelConstPtr& robot_model, - const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, bool use_signed_distance_field, double resolution, double collision_tolerance, - double max_propogation_distance, double padding, double scale) - : CollisionRobotFCL(robot_model) -{ - crobot_distance_.reset(new collision_detection::CollisionRobotDistanceField( - robot_model, link_body_decompositions, size_x, size_y, size_z, use_signed_distance_field, resolution, - collision_tolerance, max_propogation_distance, padding, scale)); -} - -CollisionRobotHybrid::CollisionRobotHybrid(const CollisionRobotHybrid& other) : CollisionRobotFCL(other) -{ - crobot_distance_.reset( - new collision_detection::CollisionRobotDistanceField(*other.getCollisionRobotDistanceField().get())); -} - -void CollisionRobotHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const robot_state::RobotState& state) const -{ - crobot_distance_->checkSelfCollision(req, res, state); -} - -void CollisionRobotHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const -{ - crobot_distance_->checkSelfCollision(req, res, state, gsr); -} - -void CollisionRobotHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const robot_state::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm) const -{ - crobot_distance_->checkSelfCollision(req, res, state, acm); -} - -void CollisionRobotHybrid::checkSelfCollisionDistanceField(const collision_detection::CollisionRequest& req, - collision_detection::CollisionResult& res, - const robot_state::RobotState& state, - const collision_detection::AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const -{ - crobot_distance_->checkSelfCollision(req, res, state, acm, gsr); -} -} // namespace collision_detection diff --git a/moveit_core/collision_distance_field/src/collision_world_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_world_distance_field.cpp deleted file mode 100644 index f9d0fb515b..0000000000 --- a/moveit_core/collision_distance_field/src/collision_world_distance_field.cpp +++ /dev/null @@ -1,568 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#include -#include -#include -#include -#include -#include -#include - -namespace collision_detection -{ -CollisionWorldDistanceField::~CollisionWorldDistanceField() -{ - getWorld()->removeObserver(observer_handle_); -} - -CollisionWorldDistanceField::CollisionWorldDistanceField(Eigen::Vector3d size, Eigen::Vector3d origin, - bool use_signed_distance_field, double resolution, - double collision_tolerance, double max_propogation_distance) - : CollisionWorld() - , size_(std::move(size)) - , origin_(std::move(origin)) - , use_signed_distance_field_(use_signed_distance_field) - , resolution_(resolution) - , collision_tolerance_(collision_tolerance) - , max_propogation_distance_(max_propogation_distance) -{ - distance_field_cache_entry_ = generateDistanceFieldCacheEntry(); - - // request notifications about changes to world - observer_handle_ = - getWorld()->addObserver(boost::bind(&CollisionWorldDistanceField::notifyObjectChange, this, _1, _2)); -} - -CollisionWorldDistanceField::CollisionWorldDistanceField(const WorldPtr& world, Eigen::Vector3d size, - Eigen::Vector3d origin, bool use_signed_distance_field, - double resolution, double collision_tolerance, - double max_propogation_distance) - : CollisionWorld(world) - , size_(std::move(size)) - , origin_(std::move(origin)) - , use_signed_distance_field_(use_signed_distance_field) - , resolution_(resolution) - , collision_tolerance_(collision_tolerance) - , max_propogation_distance_(max_propogation_distance) -{ - distance_field_cache_entry_ = generateDistanceFieldCacheEntry(); - - // request notifications about changes to world - observer_handle_ = - getWorld()->addObserver(boost::bind(&CollisionWorldDistanceField::notifyObjectChange, this, _1, _2)); - getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); -} - -CollisionWorldDistanceField::CollisionWorldDistanceField(const CollisionWorldDistanceField& other, - const WorldPtr& world) - : CollisionWorld(other, world) -{ - size_ = other.size_; - origin_ = other.origin_; - use_signed_distance_field_ = other.use_signed_distance_field_; - resolution_ = other.resolution_; - collision_tolerance_ = other.collision_tolerance_; - max_propogation_distance_ = other.max_propogation_distance_; - distance_field_cache_entry_ = generateDistanceFieldCacheEntry(); - - // request notifications about changes to world - observer_handle_ = - getWorld()->addObserver(boost::bind(&CollisionWorldDistanceField::notifyObjectChange, this, _1, _2)); - getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); -} - -void CollisionWorldDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - GroupStateRepresentationPtr gsr; - checkCollision(req, res, robot, state, gsr); -} - -void CollisionWorldDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const -{ - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, true); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - bool done = cdr.getSelfCollisions(req, res, gsr); - if (!done) - { - done = cdr.getIntraGroupCollisions(req, res, gsr); - } - if (!done) - { - getEnvironmentCollisions(req, res, distance_field_cache_entry_->distance_field_, gsr); - } - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } - - (const_cast(this))->last_gsr_ = gsr; -} - -void CollisionWorldDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - GroupStateRepresentationPtr gsr; - checkCollision(req, res, robot, state, acm, gsr); -} - -void CollisionWorldDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const -{ - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - bool done = cdr.getSelfCollisions(req, res, gsr); - if (!done) - { - done = cdr.getIntraGroupCollisions(req, res, gsr); - } - if (!done) - { - getEnvironmentCollisions(req, res, distance_field_cache_entry_->distance_field_, gsr); - } - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } - - (const_cast(this))->last_gsr_ = gsr; -} - -void CollisionWorldDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - GroupStateRepresentationPtr gsr; - checkRobotCollision(req, res, robot, state, gsr); -} - -void CollisionWorldDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const -{ - distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_->distance_field_; - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - DistanceFieldCacheEntryConstPtr dfce; - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, false); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - getEnvironmentCollisions(req, res, env_distance_field, gsr); - (const_cast(this))->last_gsr_ = gsr; - - // checkRobotCollisionHelper(req, res, robot, state, &acm); - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } -} - -void CollisionWorldDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - GroupStateRepresentationPtr gsr; - checkRobotCollision(req, res, robot, state, acm, gsr); -} - -void CollisionWorldDistanceField::checkRobotCollision(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const -{ - distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_->distance_field_; - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - DistanceFieldCacheEntryPtr dfce; - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - getEnvironmentCollisions(req, res, env_distance_field, gsr); - (const_cast(this))->last_gsr_ = gsr; - - // checkRobotCollisionHelper(req, res, robot, state, &acm); - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } -} - -void CollisionWorldDistanceField::getCollisionGradients(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const -{ - distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_->distance_field_; - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - cdr.getSelfProximityGradients(gsr); - cdr.getIntraGroupProximityGradients(gsr); - getEnvironmentProximityGradients(env_distance_field, gsr); - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } - - (const_cast(this))->last_gsr_ = gsr; -} - -void CollisionWorldDistanceField::getAllCollisions(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const -{ - try - { - const CollisionRobotDistanceField& cdr = dynamic_cast(robot); - if (!gsr) - { - cdr.generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true); - } - else - { - cdr.updateGroupStateRepresentationState(state, gsr); - } - cdr.getSelfCollisions(req, res, gsr); - cdr.getIntraGroupCollisions(req, res, gsr); - distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_->distance_field_; - getEnvironmentCollisions(req, res, env_distance_field, gsr); - } - catch (const std::bad_cast& e) - { - ROS_ERROR_STREAM("Could not cast CollisionRobot to CollisionRobotDistanceField, " << e.what()); - return; - } - - (const_cast(this))->last_gsr_ = gsr; -} - -bool CollisionWorldDistanceField::getEnvironmentCollisions( - const CollisionRequest& req, CollisionResult& res, const distance_field::DistanceFieldConstPtr& env_distance_field, - GroupStateRepresentationPtr& gsr) const -{ - for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++) - { - bool is_link = i < gsr->dfce_->link_names_.size(); - std::string link_name = i < gsr->dfce_->link_names_.size() ? gsr->dfce_->link_names_[i] : "attached"; - if (is_link && !gsr->dfce_->link_has_geometry_[i]) - { - continue; - } - - const std::vector* collision_spheres_1; - const EigenSTL::vector_Vector3d* sphere_centers_1; - - if (is_link) - { - collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres()); - sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters()); - } - else - { - collision_spheres_1 = - &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres()); - sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()); - } - - if (req.contacts) - { - std::vector colls; - bool coll = getCollisionSphereCollision( - env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, max_propogation_distance_, - collision_tolerance_, std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls); - if (coll) - { - res.collision = true; - for (unsigned int col : colls) - { - Contact con; - if (is_link) - { - con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col]; - con.body_type_1 = BodyTypes::ROBOT_LINK; - con.body_name_1 = gsr->dfce_->link_names_[i]; - } - else - { - con.pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col]; - con.body_type_1 = BodyTypes::ROBOT_ATTACHED; - con.body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()]; - } - - con.body_type_2 = BodyTypes::WORLD_OBJECT; - con.body_name_2 = "environment"; - res.contact_count++; - res.contacts[std::pair(con.body_name_1, con.body_name_2)].push_back(con); - gsr->gradients_[i].types[col] = ENVIRONMENT; - // ROS_DEBUG_STREAM("Link " << dfce->link_names_[i] << " sphere " << - // colls[j] << " in env collision"); - } - - gsr->gradients_[i].collision = true; - if (res.contact_count >= req.max_contacts) - { - return true; - } - } - } - else - { - bool coll = getCollisionSphereCollision(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, - max_propogation_distance_, collision_tolerance_); - if (coll) - { - res.collision = true; - return true; - } - } - } - return (res.contact_count >= req.max_contacts); -} - -bool CollisionWorldDistanceField::getEnvironmentProximityGradients( - const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr) const -{ - bool in_collision = false; - for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++) - { - bool is_link = i < gsr->dfce_->link_names_.size(); - - if (is_link && !gsr->dfce_->link_has_geometry_[i]) - { - continue; - } - - const std::vector* collision_spheres_1; - const EigenSTL::vector_Vector3d* sphere_centers_1; - if (is_link) - { - collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres()); - sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters()); - } - else - { - collision_spheres_1 = - &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres()); - sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()); - } - - bool coll = getCollisionSphereGradients(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1, - gsr->gradients_[i], ENVIRONMENT, collision_tolerance_, false, - max_propogation_distance_, false); - if (coll) - { - in_collision = true; - } - } - return in_collision; -} - -void CollisionWorldDistanceField::setWorld(const WorldPtr& world) -{ - if (world == getWorld()) - return; - - // turn off notifications about old world - getWorld()->removeObserver(observer_handle_); - - // clear out objects from old world - distance_field_cache_entry_->distance_field_->reset(); - - CollisionWorld::setWorld(world); - - // request notifications about changes to new world - observer_handle_ = - getWorld()->addObserver(boost::bind(&CollisionWorldDistanceField::notifyObjectChange, this, _1, _2)); - - // get notifications any objects already in the new world - getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE); -} - -void CollisionWorldDistanceField::notifyObjectChange(CollisionWorldDistanceField* self, const ObjectConstPtr& obj, - World::Action action) -{ - ros::WallTime n = ros::WallTime::now(); - - EigenSTL::vector_Vector3d add_points; - EigenSTL::vector_Vector3d subtract_points; - self->updateDistanceObject(obj->id_, self->distance_field_cache_entry_, add_points, subtract_points); - - if (action == World::DESTROY) - { - self->distance_field_cache_entry_->distance_field_->removePointsFromField(subtract_points); - } - else if (action & (World::MOVE_SHAPE | World::REMOVE_SHAPE)) - { - self->distance_field_cache_entry_->distance_field_->removePointsFromField(subtract_points); - self->distance_field_cache_entry_->distance_field_->addPointsToField(add_points); - } - else - { - self->distance_field_cache_entry_->distance_field_->addPointsToField(add_points); - } - - ROS_DEBUG_NAMED("collision_distance_field", "Modifying object %s took %lf s", obj->id_.c_str(), - (ros::WallTime::now() - n).toSec()); -} - -void CollisionWorldDistanceField::updateDistanceObject(const std::string& id, DistanceFieldCacheEntryPtr& dfce, - EigenSTL::vector_Vector3d& add_points, - EigenSTL::vector_Vector3d& subtract_points) -{ - std::map>::iterator cur_it = - dfce->posed_body_point_decompositions_.find(id); - if (cur_it != dfce->posed_body_point_decompositions_.end()) - { - for (collision_detection::PosedBodyPointDecompositionPtr& posed_body_point_decomposition : cur_it->second) - { - subtract_points.insert(subtract_points.end(), posed_body_point_decomposition->getCollisionPoints().begin(), - posed_body_point_decomposition->getCollisionPoints().end()); - } - } - - World::ObjectConstPtr object = getWorld()->getObject(id); - if (object) - { - ROS_DEBUG_STREAM("Updating/Adding Object '" << object->id_ << "' with " << object->shapes_.size() - << " shapes to CollisionWorldDistanceField"); - std::vector shape_points; - for (unsigned int i = 0; i < object->shapes_.size(); i++) - { - shapes::ShapeConstPtr shape = object->shapes_[i]; - if (shape->type == shapes::OCTREE) - { - const shapes::OcTree* octree_shape = static_cast(shape.get()); - std::shared_ptr octree = octree_shape->octree; - - shape_points.push_back(std::make_shared(octree)); - } - else - { - BodyDecompositionConstPtr bd = getBodyDecompositionCacheEntry(shape, resolution_); - - shape_points.push_back(std::make_shared(bd, object->shape_poses_[i])); - } - - add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(), - shape_points.back()->getCollisionPoints().end()); - } - - dfce->posed_body_point_decompositions_[id] = shape_points; - } - else - { - ROS_DEBUG_STREAM("Removing Object '" << id << "' from CollisionWorldDistanceField"); - dfce->posed_body_point_decompositions_.erase(id); - } -} - -CollisionWorldDistanceField::DistanceFieldCacheEntryPtr CollisionWorldDistanceField::generateDistanceFieldCacheEntry() -{ - DistanceFieldCacheEntryPtr dfce(new DistanceFieldCacheEntry()); - dfce->distance_field_.reset(new distance_field::PropagationDistanceField( - size_.x(), size_.y(), size_.z(), resolution_, origin_.x() - 0.5 * size_.x(), origin_.y() - 0.5 * size_.y(), - origin_.z() - 0.5 * size_.z(), max_propogation_distance_, use_signed_distance_field_)); - - EigenSTL::vector_Vector3d add_points; - EigenSTL::vector_Vector3d subtract_points; - for (const std::pair& object : *getWorld()) - { - updateDistanceObject(object.first, dfce, add_points, subtract_points); - } - dfce->distance_field_->addPointsToField(add_points); - return dfce; -} -} // namespace collision_detection - -#include -const std::string collision_detection::CollisionDetectorAllocatorDistanceField::NAME("DISTANCE_FIELD"); diff --git a/moveit_core/collision_distance_field/src/collision_world_hybrid.cpp b/moveit_core/collision_distance_field/src/collision_world_hybrid.cpp deleted file mode 100644 index 551937cd6a..0000000000 --- a/moveit_core/collision_distance_field/src/collision_world_hybrid.cpp +++ /dev/null @@ -1,160 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of the Willow Garage nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: E. Gil Jones */ - -#include -#include - -namespace collision_detection -{ -CollisionWorldHybrid::CollisionWorldHybrid(Eigen::Vector3d size, Eigen::Vector3d origin, bool use_signed_distance_field, - double resolution, double collision_tolerance, - double max_propogation_distance) - : CollisionWorldFCL() - , cworld_distance_(new collision_detection::CollisionWorldDistanceField( - getWorld(), std::move(size), std::move(origin), use_signed_distance_field, resolution, collision_tolerance, - max_propogation_distance)) - -{ -} - -CollisionWorldHybrid::CollisionWorldHybrid(const WorldPtr& world, Eigen::Vector3d size, Eigen::Vector3d origin, - bool use_signed_distance_field, double resolution, - double collision_tolerance, double max_propogation_distance) - : CollisionWorldFCL(world) - , cworld_distance_(new collision_detection::CollisionWorldDistanceField( - getWorld(), std::move(size), std::move(origin), use_signed_distance_field, resolution, collision_tolerance, - max_propogation_distance)) -{ -} - -CollisionWorldHybrid::CollisionWorldHybrid(const CollisionWorldHybrid& other, const WorldPtr& world) - : CollisionWorldFCL(other, world) - , cworld_distance_( - new collision_detection::CollisionWorldDistanceField(*other.getCollisionWorldDistanceField(), world)) -{ -} - -void CollisionWorldHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - cworld_distance_->checkCollision(req, res, robot, state); -} - -void CollisionWorldHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->checkCollision(req, res, robot, state, gsr); -} - -void CollisionWorldHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - cworld_distance_->checkCollision(req, res, robot, state, acm); -} - -void CollisionWorldHybrid::checkCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->checkCollision(req, res, robot, state, acm, gsr); -} - -void CollisionWorldHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state) const -{ - cworld_distance_->checkRobotCollision(req, res, robot, state); -} - -void CollisionWorldHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->checkRobotCollision(req, res, robot, state, gsr); -} - -void CollisionWorldHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm) const -{ - cworld_distance_->checkRobotCollision(req, res, robot, state, acm); -} - -void CollisionWorldHybrid::checkRobotCollisionDistanceField(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, - const robot_state::RobotState& state, - const AllowedCollisionMatrix& acm, - GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->checkRobotCollision(req, res, robot, state, acm, gsr); -} - -void CollisionWorldHybrid::setWorld(const WorldPtr& world) -{ - if (world == getWorld()) - return; - - cworld_distance_->setWorld(world); - CollisionWorldFCL::setWorld(world); -} - -void CollisionWorldHybrid::getCollisionGradients(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm, - GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->getCollisionGradients(req, res, robot, state, acm, gsr); -} - -void CollisionWorldHybrid::getAllCollisions(const CollisionRequest& req, CollisionResult& res, - const CollisionRobot& robot, const robot_state::RobotState& state, - const AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr) const -{ - cworld_distance_->getAllCollisions(req, res, robot, state, acm, gsr); -} -} // namespace collision_detection - -#include -const std::string collision_detection::CollisionDetectorAllocatorHybrid::NAME("HYBRID"); diff --git a/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp b/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp index 19445964db..c744150492 100644 --- a/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp +++ b/moveit_core/collision_distance_field/test/test_collision_distance_field.cpp @@ -38,8 +38,7 @@ #include #include #include -#include -#include +#include #include #include @@ -53,8 +52,7 @@ #include -typedef collision_detection::CollisionWorldDistanceField DefaultCWorldType; -typedef collision_detection::CollisionRobotDistanceField DefaultCRobotType; +typedef collision_detection::CollisionEnvDistanceField DefaultCEnvType; class DistanceFieldCollisionDetectionTester : public testing::Test { @@ -87,8 +85,7 @@ class DistanceFieldCollisionDetectionTester : public testing::Test acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), true)); std::map> link_body_decompositions; - crobot_.reset(new DefaultCRobotType(robot_model_, link_body_decompositions)); - cworld_.reset(new DefaultCWorldType()); + cenv_.reset(new DefaultCEnvType(robot_model_, link_body_decompositions)); } void TearDown() override @@ -107,8 +104,7 @@ class DistanceFieldCollisionDetectionTester : public testing::Test robot_state::TransformsPtr ftf_; robot_state::TransformsConstPtr ftf_const_; - collision_detection::CollisionRobotPtr crobot_; - collision_detection::CollisionWorldPtr cworld_; + collision_detection::CollisionEnvPtr cenv_; collision_detection::AllowedCollisionMatrixPtr acm_; }; @@ -124,7 +120,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, DefaultNotInCollision) collision_detection::CollisionRequest req; collision_detection::CollisionResult res; req.group_name = "whole_body"; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_FALSE(res.collision); } @@ -139,13 +135,13 @@ TEST_F(DistanceFieldCollisionDetectionTester, ChangeTorsoPosition) collision_detection::CollisionResult res2; req.group_name = "right_arm"; - crobot_->checkSelfCollision(req, res1, robot_state, *acm_); + cenv_->checkSelfCollision(req, res1, robot_state, *acm_); std::map torso_val; torso_val["torso_lift_joint"] = .15; robot_state.setVariablePositions(torso_val); robot_state.update(); - crobot_->checkSelfCollision(req, res1, robot_state, *acm_); - crobot_->checkSelfCollision(req, res1, robot_state, *acm_); + cenv_->checkSelfCollision(req, res1, robot_state, *acm_); + cenv_->checkSelfCollision(req, res1, robot_state, *acm_); } TEST_F(DistanceFieldCollisionDetectionTester, LinksInCollision) @@ -168,18 +164,18 @@ TEST_F(DistanceFieldCollisionDetectionTester, LinksInCollision) robot_state.updateStateWithLinkAt("base_bellow_link", offset); acm_->setEntry("base_link", "base_bellow_link", false); - crobot_->checkSelfCollision(req, res1, robot_state, *acm_); + cenv_->checkSelfCollision(req, res1, robot_state, *acm_); ASSERT_TRUE(res1.collision); acm_->setEntry("base_link", "base_bellow_link", true); - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + cenv_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_FALSE(res2.collision); robot_state.updateStateWithLinkAt("r_gripper_palm_link", Eigen::Isometry3d::Identity()); robot_state.updateStateWithLinkAt("l_gripper_palm_link", offset); acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); - crobot_->checkSelfCollision(req, res3, robot_state, *acm_); + cenv_->checkSelfCollision(req, res3, robot_state, *acm_); ASSERT_TRUE(res3.collision); } @@ -206,7 +202,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactReporting) acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); collision_detection::CollisionResult res; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_EQ(res.contacts.size(), 1u); EXPECT_EQ(res.contacts.begin()->second.size(), 1u); @@ -215,7 +211,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactReporting) req.max_contacts = 2; req.max_contacts_per_pair = 1; // req.verbose = true; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_EQ(res.contact_count, 2u); EXPECT_EQ(res.contacts.begin()->second.size(), 1u); @@ -226,7 +222,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactReporting) req.max_contacts = 10; req.max_contacts_per_pair = 2; acm_.reset(new collision_detection::AllowedCollisionMatrix(robot_model_->getLinkModelNames(), false)); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); EXPECT_LE(res.contacts.size(), 10u); EXPECT_LE(res.contact_count, 10u); @@ -254,7 +250,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactPositions) acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false); collision_detection::CollisionResult res; - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); ASSERT_EQ(res.contacts.size(), 1u); ASSERT_EQ(res.contacts.begin()->second.size(), 1u); @@ -272,7 +268,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactPositions) robot_state.updateStateWithLinkAt("l_gripper_palm_link", pos2); collision_detection::CollisionResult res2; - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + cenv_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_TRUE(res2.collision); ASSERT_EQ(res2.contacts.size(), 1u); ASSERT_EQ(res2.contacts.begin()->second.size(), 1u); @@ -290,7 +286,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, ContactPositions) robot_state.updateStateWithLinkAt("l_gripper_palm_link", pos2); collision_detection::CollisionResult res3; - crobot_->checkSelfCollision(req, res2, robot_state, *acm_); + cenv_->checkSelfCollision(req, res2, robot_state, *acm_); ASSERT_FALSE(res3.collision); } @@ -311,18 +307,18 @@ TEST_F(DistanceFieldCollisionDetectionTester, AttachedBodyTester) pos1.translation().x() = 1.0; robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_FALSE(res.collision); shapes::Shape* shape = new shapes::Box(.25, .25, .25); - cworld_->getWorld()->addToObject("box", shapes::ShapeConstPtr(shape), pos1); + cenv_->getWorld()->addToObject("box", shapes::ShapeConstPtr(shape), pos1); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + cenv_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); // deletes shape - cworld_->getWorld()->removeObject("box"); + cenv_->getWorld()->removeObject("box"); std::vector shapes; EigenSTL::vector_Isometry3d poses; @@ -336,7 +332,7 @@ TEST_F(DistanceFieldCollisionDetectionTester, AttachedBodyTester) robot_state.attachBody(attached_body); res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); // deletes shape @@ -350,19 +346,19 @@ TEST_F(DistanceFieldCollisionDetectionTester, AttachedBodyTester) robot_state.attachBody(attached_body_1); res = collision_detection::CollisionResult(); - crobot_->checkSelfCollision(req, res, robot_state, *acm_); + cenv_->checkSelfCollision(req, res, robot_state, *acm_); // ASSERT_FALSE(res.collision); pos1.translation().x() = 1.01; shapes::Shape* coll = new shapes::Box(.1, .1, .1); - cworld_->getWorld()->addToObject("coll", shapes::ShapeConstPtr(coll), pos1); + cenv_->getWorld()->addToObject("coll", shapes::ShapeConstPtr(coll), pos1); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + cenv_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); acm_->setEntry("coll", "r_gripper_palm_link", true); res = collision_detection::CollisionResult(); - cworld_->checkRobotCollision(req, res, *crobot_, robot_state, *acm_); + cenv_->checkRobotCollision(req, res, robot_state, *acm_); ASSERT_TRUE(res.collision); } diff --git a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h index 4d15e35d63..a716e8bd86 100644 --- a/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h +++ b/moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include @@ -831,7 +831,7 @@ class VisibilityConstraint : public KinematicConstraint */ bool decideContact(const collision_detection::Contact& contact) const; - collision_detection::CollisionRobotPtr collision_robot_; /**< \brief A copy of the collision robot maintained for + collision_detection::CollisionEnvPtr collision_env_; /**< \brief A copy of the collision robot maintained for collision checking the cone against robot links */ bool mobile_sensor_frame_; /**< \brief True if the sensor is a non-fixed frame relative to the transform frame */ bool mobile_target_frame_; /**< \brief True if the target is a non-fixed frame relative to the transform frame */ diff --git a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp index 526fe4e3d3..884a1dca51 100644 --- a/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp +++ b/moveit_core/kinematic_constraints/src/kinematic_constraint.cpp @@ -38,8 +38,7 @@ #include #include #include -#include -#include +#include #include #include #include @@ -644,7 +643,7 @@ void OrientationConstraint::print(std::ostream& out) const } VisibilityConstraint::VisibilityConstraint(const robot_model::RobotModelConstPtr& model) - : KinematicConstraint(model), collision_robot_(new collision_detection::CollisionRobotFCL(model)) + : KinematicConstraint(model), collision_env_(new collision_detection::CollisionEnvFCL(model)) { type_ = VISIBILITY_CONSTRAINT; } @@ -984,8 +983,7 @@ ConstraintEvaluationResult VisibilityConstraint::decide(const robot_state::Robot return ConstraintEvaluationResult(false, 0.0); // add the visibility cone as an object - collision_detection::CollisionWorldFCL collision_world; - collision_world.getWorld()->addToObject("cone", shapes::ShapeConstPtr(m), Eigen::Isometry3d::Identity()); + collision_env_->getWorld()->addToObject("cone", shapes::ShapeConstPtr(m), Eigen::Isometry3d::Identity()); // check for collisions between the robot and the cone collision_detection::CollisionRequest req; @@ -995,7 +993,7 @@ ConstraintEvaluationResult VisibilityConstraint::decide(const robot_state::Robot req.contacts = true; req.verbose = verbose; req.max_contacts = 1; - collision_world.checkRobotCollision(req, res, *collision_robot_, state, acm); + collision_env_->checkRobotCollision(req, res, state, acm); if (verbose) { @@ -1005,6 +1003,8 @@ ConstraintEvaluationResult VisibilityConstraint::decide(const robot_state::Robot res.collision ? "not " : "", ss.str().c_str()); } + collision_env_->getWorld()->removeObject("cone"); + return ConstraintEvaluationResult(!res.collision, res.collision ? res.contacts.begin()->second.front().depth : 0.0); } diff --git a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h index c7954cce12..6faff3b6aa 100644 --- a/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h +++ b/moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -293,43 +294,31 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from return world_; } - /** \brief Get the active collision detector for the world */ - const collision_detection::CollisionWorldConstPtr& getCollisionWorld() const + /** \brief Get the active collision environment */ + const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const { - // we always have a world representation after configure is called. - return active_collision_->cworld_const_; + return active_collision_->getCollisionEnv(); } /** \brief Get the active collision detector for the robot */ - const collision_detection::CollisionRobotConstPtr& getCollisionRobot() const + const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const { - return active_collision_->getCollisionRobot(); - } - - /** \brief Get the active collision detector for the robot */ - const collision_detection::CollisionRobotConstPtr& getCollisionRobotUnpadded() const - { - return active_collision_->getCollisionRobotUnpadded(); + return active_collision_->getCollisionEnvUnpadded(); } /** \brief Get a specific collision detector for the world. If not found return active CollisionWorld. */ - const collision_detection::CollisionWorldConstPtr& - getCollisionWorld(const std::string& collision_detector_name) const; - - /** \brief Get a specific collision detector for the padded robot. If no found return active CollisionRobot. */ - const collision_detection::CollisionRobotConstPtr& - getCollisionRobot(const std::string& collision_detector_name) const; + const collision_detection::CollisionEnvConstPtr& getCollisionEnv(const std::string& collision_detector_name) const; /** \brief Get a specific collision detector for the unpadded robot. If no found return active unpadded * CollisionRobot. */ - const collision_detection::CollisionRobotConstPtr& - getCollisionRobotUnpadded(const std::string& collision_detector_name) const; + const collision_detection::CollisionEnvConstPtr& + getCollisionEnvUnpadded(const std::string& collision_detector_name) const; /** \brief Get the representation of the collision robot * This can be used to set padding and link scale on the active collision_robot. * NOTE: After modifying padding and scale on the active robot call * propogateRobotPadding() to copy it to all the other collision detectors. */ - const collision_detection::CollisionRobotPtr& getCollisionRobotNonConst(); + const collision_detection::CollisionEnvPtr& getCollisionEnvNonConst(); /** \brief Copy scale and padding from active CollisionRobot to other CollisionRobots. * This should be called after any changes are made to the scale or padding of the active @@ -501,7 +490,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from const robot_state::RobotState& robot_state) const { // do self-collision checking with the unpadded version of the robot - getCollisionRobotUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); } /** \brief Check whether a specified state (\e robot_state) is in self collision, with respect to a given @@ -521,7 +510,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from const collision_detection::AllowedCollisionMatrix& acm) const { // do self-collision checking with the unpadded version of the robot - getCollisionRobotUnpadded()->checkSelfCollision(req, res, robot_state, acm); + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); } /** \brief Get the names of the links that are involved in collisions for the current state */ @@ -624,7 +613,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from */ double distanceToCollision(const robot_state::RobotState& robot_state) const { - return getCollisionWorld()->distanceRobot(*getCollisionRobot(), robot_state, getAllowedCollisionMatrix()); + return getCollisionEnv()->distanceRobot(robot_state, getAllowedCollisionMatrix()); } /** \brief The distance between the robot model at state \e robot_state to the nearest collision (ignoring @@ -639,7 +628,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from * self-collisions), if the robot has no padding */ double distanceToCollisionUnpadded(const robot_state::RobotState& robot_state) const { - return getCollisionWorld()->distanceRobot(*getCollisionRobotUnpadded(), robot_state, getAllowedCollisionMatrix()); + return getCollisionEnvUnpadded()->distanceRobot(robot_state, getAllowedCollisionMatrix()); } /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring @@ -658,7 +647,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from double distanceToCollision(const robot_state::RobotState& robot_state, const collision_detection::AllowedCollisionMatrix& acm) const { - return getCollisionWorld()->distanceRobot(*getCollisionRobot(), robot_state, acm); + return getCollisionEnv()->distanceRobot(robot_state, acm); } /** \brief The distance between the robot model at state \e robot_state to the nearest collision, ignoring @@ -677,7 +666,7 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from double distanceToCollisionUnpadded(const robot_state::RobotState& robot_state, const collision_detection::AllowedCollisionMatrix& acm) const { - return getCollisionWorld()->distanceRobot(*getCollisionRobotUnpadded(), robot_state, acm); + return getCollisionEnvUnpadded()->distanceRobot(robot_state, acm); } /**@}*/ @@ -993,23 +982,21 @@ class PlanningScene : private boost::noncopyable, public std::enable_shared_from struct CollisionDetector { collision_detection::CollisionDetectorAllocatorPtr alloc_; - collision_detection::CollisionRobotPtr crobot_unpadded_; // if NULL use parent's - collision_detection::CollisionRobotConstPtr crobot_unpadded_const_; - collision_detection::CollisionRobotPtr crobot_; // if NULL use parent's - collision_detection::CollisionRobotConstPtr crobot_const_; + collision_detection::CollisionEnvPtr cenv_; // never NULL + collision_detection::CollisionEnvConstPtr cenv_const_; - collision_detection::CollisionWorldPtr cworld_; // never NULL - collision_detection::CollisionWorldConstPtr cworld_const_; + collision_detection::CollisionEnvPtr cenv_unpadded_; + collision_detection::CollisionEnvConstPtr cenv_unpadded_const_; CollisionDetectorConstPtr parent_; // may be NULL - const collision_detection::CollisionRobotConstPtr& getCollisionRobot() const + const collision_detection::CollisionEnvConstPtr& getCollisionEnv() const { - return crobot_const_ ? crobot_const_ : parent_->getCollisionRobot(); + return cenv_const_ ? cenv_const_ : parent_->getCollisionEnv(); } - const collision_detection::CollisionRobotConstPtr& getCollisionRobotUnpadded() const + const collision_detection::CollisionEnvConstPtr& getCollisionEnvUnpadded() const { - return crobot_unpadded_const_ ? crobot_unpadded_const_ : parent_->getCollisionRobotUnpadded(); + return cenv_unpadded_const_ ? cenv_unpadded_const_ : parent_->getCollisionEnvUnpadded(); } void findParent(const PlanningScene& scene); void copyPadding(const CollisionDetector& src); diff --git a/moveit_core/planning_scene/src/planning_scene.cpp b/moveit_core/planning_scene/src/planning_scene.cpp index 279f824e83..ed8a94dac9 100644 --- a/moveit_core/planning_scene/src/planning_scene.cpp +++ b/moveit_core/planning_scene/src/planning_scene.cpp @@ -201,15 +201,13 @@ PlanningScene::PlanningScene(const PlanningSceneConstPtr& parent) : parent_(pare detector->alloc_ = parent_detector->alloc_; detector->parent_ = parent_detector; - detector->cworld_ = detector->alloc_->allocateWorld(parent_detector->cworld_, world_); - detector->cworld_const_ = detector->cworld_; + detector->cenv_ = detector->alloc_->allocateEnv(parent_detector->cenv_, world_); + detector->cenv_const_ = detector->cenv_; - // leave these empty and use parent collision_robot_ unless/until a non-const one + // leave these empty and use parent collision_env_ unless/until a non-const one // is requested (e.g. to modify link padding or scale) - detector->crobot_.reset(); - detector->crobot_const_.reset(); - detector->crobot_unpadded_.reset(); - detector->crobot_unpadded_const_.reset(); + detector->cenv_unpadded_.reset(); + detector->cenv_unpadded_const_.reset(); } setActiveCollisionDetector(parent_->getActiveCollisionDetectorName()); } @@ -236,21 +234,12 @@ PlanningScenePtr PlanningScene::diff(const moveit_msgs::PlanningScene& msg) cons void PlanningScene::CollisionDetector::copyPadding(const PlanningScene::CollisionDetector& src) { - if (!crobot_) - { - alloc_->allocateRobot(parent_->getCollisionRobot()); - crobot_const_ = crobot_; - } - - crobot_->setLinkPadding(src.getCollisionRobot()->getLinkPadding()); - crobot_->setLinkScale(src.getCollisionRobot()->getLinkScale()); + cenv_->setLinkPadding(src.getCollisionEnv()->getLinkPadding()); + cenv_->setLinkScale(src.getCollisionEnv()->getLinkScale()); } void PlanningScene::propogateRobotPadding() { - if (!active_collision_->crobot_) - return; - for (std::pair& it : collision_) { if (it.second != active_collision_) @@ -285,25 +274,23 @@ void PlanningScene::addCollisionDetector(const collision_detection::CollisionDet detector->findParent(*this); - detector->cworld_ = detector->alloc_->allocateWorld(world_); - detector->cworld_const_ = detector->cworld_; + detector->cenv_ = detector->alloc_->allocateEnv(world_, getRobotModel()); + detector->cenv_const_ = detector->cenv_; - // Allocate CollisionRobot unless we can use the parent's crobot_. - // If active_collision_->crobot_ is non-NULL there is local padding and we cannot use the parent's crobot_. - if (!detector->parent_ || active_collision_->crobot_) + // if the current active detector is not the added one, copy its padding to the new one and allocate unpadded + if (detector != active_collision_) { - detector->crobot_ = detector->alloc_->allocateRobot(getRobotModel()); - detector->crobot_const_ = detector->crobot_; + detector->cenv_unpadded_ = detector->alloc_->allocateEnv(world_, getRobotModel()); + detector->cenv_unpadded_const_ = detector->cenv_unpadded_; - if (detector != active_collision_) - detector->copyPadding(*active_collision_); + detector->copyPadding(*active_collision_); } - // Allocate CollisionRobot unless we can use the parent's crobot_unpadded_. + // If we don't have a parent, allocate unpadded versions, otherwise use the parent's cenv_unpadded_. if (!detector->parent_) { - detector->crobot_unpadded_ = detector->alloc_->allocateRobot(getRobotModel()); - detector->crobot_unpadded_const_ = detector->crobot_unpadded_; + detector->cenv_unpadded_ = detector->alloc_->allocateEnv(world_, getRobotModel()); + detector->cenv_unpadded_const_ = detector->cenv_unpadded_; } } @@ -357,36 +344,22 @@ void PlanningScene::getCollisionDetectorNames(std::vector& names) c names.push_back(it.first); } -const collision_detection::CollisionWorldConstPtr& -PlanningScene::getCollisionWorld(const std::string& collision_detector_name) const -{ - CollisionDetectorConstIterator it = collision_.find(collision_detector_name); - if (it == collision_.end()) - { - ROS_ERROR_NAMED(LOGNAME, "Could not get CollisionWorld named '%s'. Returning active CollisionWorld '%s' instead", - collision_detector_name.c_str(), active_collision_->alloc_->getName().c_str()); - return active_collision_->cworld_const_; - } - - return it->second->cworld_const_; -} - -const collision_detection::CollisionRobotConstPtr& -PlanningScene::getCollisionRobot(const std::string& collision_detector_name) const +const collision_detection::CollisionEnvConstPtr& +PlanningScene::getCollisionEnv(const std::string& collision_detector_name) const { CollisionDetectorConstIterator it = collision_.find(collision_detector_name); if (it == collision_.end()) { ROS_ERROR_NAMED(LOGNAME, "Could not get CollisionRobot named '%s'. Returning active CollisionRobot '%s' instead", collision_detector_name.c_str(), active_collision_->alloc_->getName().c_str()); - return active_collision_->getCollisionRobot(); + return active_collision_->getCollisionEnv(); } - return it->second->getCollisionRobot(); + return it->second->getCollisionEnv(); } -const collision_detection::CollisionRobotConstPtr& -PlanningScene::getCollisionRobotUnpadded(const std::string& collision_detector_name) const +const collision_detection::CollisionEnvConstPtr& +PlanningScene::getCollisionEnvUnpadded(const std::string& collision_detector_name) const { CollisionDetectorConstIterator it = collision_.find(collision_detector_name); if (it == collision_.end()) @@ -394,10 +367,10 @@ PlanningScene::getCollisionRobotUnpadded(const std::string& collision_detector_n ROS_ERROR_NAMED(LOGNAME, "Could not get CollisionRobotUnpadded named '%s'. " "Returning active CollisionRobotUnpadded '%s' instead", collision_detector_name.c_str(), active_collision_->alloc_->getName().c_str()); - return active_collision_->getCollisionRobotUnpadded(); + return active_collision_->getCollisionEnvUnpadded(); } - return it->second->getCollisionRobotUnpadded(); + return it->second->getCollisionEnvUnpadded(); } void PlanningScene::clearDiffs() @@ -420,20 +393,18 @@ void PlanningScene::clearDiffs() if (it.second->parent_) { - it.second->crobot_.reset(); - it.second->crobot_const_.reset(); - it.second->crobot_unpadded_.reset(); - it.second->crobot_unpadded_const_.reset(); + it.second->cenv_unpadded_.reset(); + it.second->cenv_unpadded_const_.reset(); - it.second->cworld_ = it.second->alloc_->allocateWorld(it.second->parent_->cworld_, world_); - it.second->cworld_const_ = it.second->cworld_; + it.second->cenv_ = it.second->alloc_->allocateEnv(it.second->parent_->cenv_, world_); + it.second->cenv_const_ = it.second->cenv_; } else { it.second->copyPadding(*parent_->active_collision_); - it.second->cworld_ = it.second->alloc_->allocateWorld(world_); - it.second->cworld_const_ = it.second->cworld_; + it.second->cenv_ = it.second->alloc_->allocateEnv(it.second->parent_->cenv_, world_); + it.second->cenv_const_ = it.second->cenv_; } } @@ -471,13 +442,10 @@ void PlanningScene::pushDiffs(const PlanningScenePtr& scene) if (acm_) scene->getAllowedCollisionMatrixNonConst() = *acm_; - if (active_collision_->crobot_) - { - collision_detection::CollisionRobotPtr active_crobot = scene->getCollisionRobotNonConst(); - active_crobot->setLinkPadding(active_collision_->crobot_->getLinkPadding()); - active_crobot->setLinkScale(active_collision_->crobot_->getLinkScale()); - scene->propogateRobotPadding(); - } + collision_detection::CollisionEnvPtr active_cenv = scene->getCollisionEnvNonConst(); + active_cenv->setLinkPadding(active_collision_->cenv_->getLinkPadding()); + active_cenv->setLinkScale(active_collision_->cenv_->getLinkScale()); + scene->propogateRobotPadding(); if (world_diff_) { @@ -519,12 +487,12 @@ void PlanningScene::checkCollision(const collision_detection::CollisionRequest& const robot_state::RobotState& robot_state) const { // check collision with the world using the padded version - getCollisionWorld()->checkRobotCollision(req, res, *getCollisionRobot(), robot_state, getAllowedCollisionMatrix()); + getCollisionEnv()->checkRobotCollision(req, res, robot_state, getAllowedCollisionMatrix()); if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) { // do self-collision checking with the unpadded version of the robot - getCollisionRobotUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, getAllowedCollisionMatrix()); } } @@ -543,11 +511,11 @@ void PlanningScene::checkCollision(const collision_detection::CollisionRequest& const collision_detection::AllowedCollisionMatrix& acm) const { // check collision with the world using the padded version - getCollisionWorld()->checkRobotCollision(req, res, *getCollisionRobot(), robot_state, acm); + getCollisionEnv()->checkRobotCollision(req, res, robot_state, acm); // do self-collision checking with the unpadded version of the robot if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) - getCollisionRobotUnpadded()->checkSelfCollision(req, res, robot_state, acm); + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); } void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionRequest& req, @@ -565,12 +533,12 @@ void PlanningScene::checkCollisionUnpadded(const collision_detection::CollisionR const collision_detection::AllowedCollisionMatrix& acm) const { // check collision with the world using the unpadded version - getCollisionWorld()->checkRobotCollision(req, res, *getCollisionRobotUnpadded(), robot_state, acm); + getCollisionEnvUnpadded()->checkRobotCollision(req, res, robot_state, acm); // do self-collision checking with the unpadded version of the robot if (!res.collision || (req.contacts && res.contacts.size() < req.max_contacts)) { - getCollisionRobotUnpadded()->checkSelfCollision(req, res, robot_state, acm); + getCollisionEnvUnpadded()->checkSelfCollision(req, res, robot_state, acm); } } @@ -620,15 +588,9 @@ void PlanningScene::getCollidingLinks(std::vector& links, const rob } } -const collision_detection::CollisionRobotPtr& PlanningScene::getCollisionRobotNonConst() +const collision_detection::CollisionEnvPtr& PlanningScene::getCollisionEnvNonConst() { - if (!active_collision_->crobot_) - { - active_collision_->crobot_ = - active_collision_->alloc_->allocateRobot(active_collision_->parent_->getCollisionRobot()); - active_collision_->crobot_const_ = active_collision_->crobot_; - } - return active_collision_->crobot_; + return active_collision_->cenv_; } robot_state::RobotState& PlanningScene::getCurrentStateNonConst() @@ -717,16 +679,8 @@ void PlanningScene::getPlanningSceneDiffMsg(moveit_msgs::PlanningScene& scene_ms else scene_msg.allowed_collision_matrix = moveit_msgs::AllowedCollisionMatrix(); - if (active_collision_->crobot_) - { - active_collision_->crobot_->getPadding(scene_msg.link_padding); - active_collision_->crobot_->getScale(scene_msg.link_scale); - } - else - { - scene_msg.link_padding.clear(); - scene_msg.link_scale.clear(); - } + active_collision_->cenv_->getPadding(scene_msg.link_padding); + active_collision_->cenv_->getScale(scene_msg.link_scale); scene_msg.object_colors.clear(); if (object_colors_) @@ -812,7 +766,7 @@ bool PlanningScene::getCollisionObjectMsg(moveit_msgs::CollisionObject& collisio collision_obj.header.frame_id = getPlanningFrame(); collision_obj.id = ns; collision_obj.operation = moveit_msgs::CollisionObject::ADD; - collision_detection::CollisionWorld::ObjectConstPtr obj = world_->getObject(ns); + collision_detection::CollisionEnv::ObjectConstPtr obj = world_->getObject(ns); if (!obj) return false; ShapeVisitorAddToCollisionObject sv(&collision_obj); @@ -884,7 +838,7 @@ bool PlanningScene::getOctomapMsg(octomap_msgs::OctomapWithPose& octomap) const octomap.header.frame_id = getPlanningFrame(); octomap.octomap = octomap_msgs::Octomap(); - collision_detection::CollisionWorld::ObjectConstPtr map = world_->getObject(OCTOMAP_NS); + collision_detection::CollisionEnv::ObjectConstPtr map = world_->getObject(OCTOMAP_NS); if (map) { if (map->shapes_.size() == 1) @@ -924,8 +878,8 @@ void PlanningScene::getPlanningSceneMsg(moveit_msgs::PlanningScene& scene_msg) c robot_state::robotStateToRobotStateMsg(getCurrentState(), scene_msg.robot_state); getAllowedCollisionMatrix().getMessage(scene_msg.allowed_collision_matrix); - getCollisionRobot()->getPadding(scene_msg.link_padding); - getCollisionRobot()->getScale(scene_msg.link_scale); + getCollisionEnv()->getPadding(scene_msg.link_padding); + getCollisionEnv()->getScale(scene_msg.link_scale); getObjectColorMsgs(scene_msg.object_colors); @@ -971,8 +925,8 @@ void PlanningScene::getPlanningSceneMsg(moveit_msgs::PlanningScene& scene_msg, if (comp.components & moveit_msgs::PlanningSceneComponents::LINK_PADDING_AND_SCALING) { - getCollisionRobot()->getPadding(scene_msg.link_padding); - getCollisionRobot()->getScale(scene_msg.link_scale); + getCollisionEnv()->getPadding(scene_msg.link_padding); + getCollisionEnv()->getScale(scene_msg.link_scale); } if (comp.components & moveit_msgs::PlanningSceneComponents::OBJECT_COLORS) @@ -1009,7 +963,7 @@ void PlanningScene::saveGeometryToStream(std::ostream& out) const for (const std::string& id : ids) if (id != OCTOMAP_NS) { - collision_detection::CollisionWorld::ObjectConstPtr obj = world_->getObject(id); + collision_detection::CollisionEnv::ObjectConstPtr obj = world_->getObject(id); if (obj) { out << "* " << id << std::endl; @@ -1184,15 +1138,10 @@ void PlanningScene::decoupleParent() for (std::pair& it : collision_) { - if (!it.second->crobot_) - { - it.second->crobot_ = it.second->alloc_->allocateRobot(it.second->parent_->getCollisionRobot()); - it.second->crobot_const_ = it.second->crobot_; - } - if (!it.second->crobot_unpadded_) + if (!it.second->cenv_unpadded_) { - it.second->crobot_unpadded_ = it.second->alloc_->allocateRobot(it.second->parent_->getCollisionRobotUnpadded()); - it.second->crobot_unpadded_const_ = it.second->crobot_unpadded_; + it.second->cenv_unpadded_ = it.second->alloc_->allocateEnv(it.second->parent_->getCollisionEnvUnpadded(), world_); + it.second->cenv_unpadded_const_ = it.second->cenv_unpadded_; } it.second->parent_.reset(); } @@ -1265,13 +1214,8 @@ bool PlanningScene::setPlanningSceneDiffMsg(const moveit_msgs::PlanningScene& sc { for (std::pair& it : collision_) { - if (!it.second->crobot_) - { - it.second->crobot_ = it.second->alloc_->allocateRobot(it.second->parent_->getCollisionRobot()); - it.second->crobot_const_ = it.second->crobot_; - } - it.second->crobot_->setPadding(scene_msg.link_padding); - it.second->crobot_->setScale(scene_msg.link_scale); + it.second->cenv_->setPadding(scene_msg.link_padding); + it.second->cenv_->setScale(scene_msg.link_scale); } } @@ -1308,13 +1252,8 @@ bool PlanningScene::setPlanningSceneMsg(const moveit_msgs::PlanningScene& scene_ acm_.reset(new collision_detection::AllowedCollisionMatrix(scene_msg.allowed_collision_matrix)); for (std::pair& it : collision_) { - if (!it.second->crobot_) - { - it.second->crobot_ = it.second->alloc_->allocateRobot(it.second->parent_->getCollisionRobot()); - it.second->crobot_const_ = it.second->crobot_; - } - it.second->crobot_->setPadding(scene_msg.link_padding); - it.second->crobot_->setScale(scene_msg.link_scale); + it.second->cenv_->setPadding(scene_msg.link_padding); + it.second->cenv_->setScale(scene_msg.link_scale); } object_colors_.reset(new ObjectColorMap()); for (const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors) @@ -1402,7 +1341,7 @@ void PlanningScene::processOctomapMsg(const octomap_msgs::OctomapWithPose& map) void PlanningScene::processOctomapPtr(const std::shared_ptr& octree, const Eigen::Isometry3d& t) { - collision_detection::CollisionWorld::ObjectConstPtr map = world_->getObject(OCTOMAP_NS); + collision_detection::CollisionEnv::ObjectConstPtr map = world_->getObject(OCTOMAP_NS); if (map) { if (map->shapes_.size() == 1) @@ -1503,7 +1442,7 @@ bool PlanningScene::processAttachedCollisionObjectMsg(const moveit_msgs::Attache // TODO(felixvd): This code may be duplicated in robot_state/conversions.cpp // STEP 1.1: Get shapes and poses from existing world object or message. - collision_detection::CollisionWorld::ObjectConstPtr obj_in_world = world_->getObject(object.object.id); + collision_detection::CollisionEnv::ObjectConstPtr obj_in_world = world_->getObject(object.object.id); if (object.object.operation == moveit_msgs::CollisionObject::ADD && object.object.primitives.empty() && object.object.meshes.empty() && object.object.planes.empty()) { diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index f98009e133..05d6c235c4 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -42,8 +42,7 @@ #include #include #include -#include -#include +#include #include #include @@ -135,8 +134,7 @@ class ChompOptimizer moveit::core::RobotState state_; moveit::core::RobotState start_state_; const moveit::core::JointModelGroup* joint_model_group_; - const collision_detection::CollisionWorldHybrid* hy_world_; - const collision_detection::CollisionRobotHybrid* hy_robot_; + const collision_detection::CollisionEnvHybrid* hy_env_; std::vector joint_costs_; collision_detection::GroupStateRepresentationPtr gsr_; diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp index 6158d6f3e5..ae30b79aad 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp @@ -75,21 +75,14 @@ ChompOptimizer::ChompOptimizer(ChompTrajectory* trajectory, const planning_scene ROS_INFO_STREAM("Active collision detector is: " + planning_scene->getActiveCollisionDetectorName()); - hy_world_ = dynamic_cast( - planning_scene->getCollisionWorld(planning_scene->getActiveCollisionDetectorName()).get()); - if (!hy_world_) + hy_env_ = dynamic_cast( + planning_scene->getCollisionEnv(planning_scene->getActiveCollisionDetectorName()).get()); + if (!hy_env_) { ROS_WARN_STREAM("Could not initialize hybrid collision world from planning scene"); return; } - hy_robot_ = dynamic_cast( - planning_scene->getCollisionRobot(planning_scene->getActiveCollisionDetectorName()).get()); - if (!hy_robot_) - { - ROS_WARN_STREAM("Could not initialize hybrid collision robot from planning scene"); - return; - } initialize(); } @@ -107,8 +100,7 @@ void ChompOptimizer::initialize() collision_detection::CollisionResult res; req.group_name = planning_group_; ros::WallTime wt = ros::WallTime::now(); - hy_world_->getCollisionGradients(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), state_, - &planning_scene_->getAllowedCollisionMatrix(), gsr_); + hy_env_->getCollisionGradients(req, res, state_, &planning_scene_->getAllowedCollisionMatrix(), gsr_); ROS_INFO_STREAM("First coll check took " << (ros::WallTime::now() - wt)); num_collision_points_ = 0; for (const collision_detection::GradientInfo& gradient : gsr_->gradients_) @@ -937,8 +929,7 @@ void ChompOptimizer::performForwardKinematics() setRobotStateFromPoint(group_trajectory_, i); ros::WallTime grad = ros::WallTime::now(); - hy_world_->getCollisionGradients(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), state_, nullptr, - gsr_); + hy_env_->getCollisionGradients(req, res, state_, nullptr, gsr_); total_dur += (ros::WallTime::now() - grad); computeJointProperties(i); state_is_in_collision_[i] = false; diff --git a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h index 5158a7f49d..53b258ced3 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h +++ b/moveit_planners/sbpl/core/sbpl_interface/include/sbpl_interface/environment_chain3d.h @@ -50,8 +50,7 @@ #include #include #include -#include -#include +#include #include #include @@ -248,8 +247,7 @@ class EnvironmentChain3D : public DiscreteSpaceInformation std::vector > joint_motion_wrappers_; std::vector > possible_actions_; planning_models::RobotState* state_; - const collision_detection::CollisionWorldHybrid* hy_world_; - const collision_detection::CollisionRobotHybrid* hy_robot_; + const collision_detection::CollisionEnvHybrid* hy_env_; planning_models::RobotState* ::JointStateGroup* joint_state_group_; boost::shared_ptr gsr_; // boost::shared_ptr kinematics_solver_; diff --git a/moveit_planners/sbpl/core/sbpl_interface/src/environment_chain3d.cpp b/moveit_planners/sbpl/core/sbpl_interface/src/environment_chain3d.cpp index 6e84c9ac11..5ff2829e1f 100644 --- a/moveit_planners/sbpl/core/sbpl_interface/src/environment_chain3d.cpp +++ b/moveit_planners/sbpl/core/sbpl_interface/src/environment_chain3d.cpp @@ -247,8 +247,7 @@ void EnvironmentChain3D::GetSuccs(int source_state_ID, std::vector* succ_id req.group_name = planning_group_; if (!planning_parameters_.use_standard_collision_checking_) { - hy_world_->checkCollisionDistanceField(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), state_, - gsr_); + hy_env_->checkCollisionDistanceField(req, res, *hy_env_->getCollisionRobotDistanceField().get(), state_, gsr_); } else { @@ -436,18 +435,16 @@ bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneC if (!planning_parameters_.use_standard_collision_checking_) { - hy_world_ = - dynamic_cast(planning_scene->getCollisionWorld().get()); - if (!hy_world_) + hy_env_ = dynamic_cast(planning_scene->getCollisionEnv().get()); + if (!hy_env_) { ROS_WARN_STREAM("Could not initialize hybrid collision world from planning scene"); mres.error_code.val = moveit_msgs::MoveItErrorCodes::COLLISION_CHECKING_UNAVAILABLE; return false; } - hy_robot_ = - dynamic_cast(planning_scene->getCollisionRobot().get()); - if (!hy_robot_) + hy_env_ = dynamic_cast(planning_scene->getCollisionEnv().get()); + if (!hy_env_) { ROS_WARN_STREAM("Could not initialize hybrid collision robot from planning scene"); mres.error_code.val = moveit_msgs::MoveItErrorCodes::COLLISION_CHECKING_UNAVAILABLE; @@ -473,8 +470,8 @@ bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneC req.group_name = planning_group_; if (!planning_parameters_.use_standard_collision_checking_) { - hy_world_->checkCollisionDistanceField(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), state_, - planning_scene_->getAllowedCollisionMatrix(), gsr_); + hy_env_->checkCollisionDistanceField(req, res, *hy_env_->getCollisionRobotDistanceField().get(), state_, + planning_scene_->getAllowedCollisionMatrix(), gsr_); } else { @@ -507,7 +504,7 @@ bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneC gsr_->dfce_->distance_field_->getZNumCells()); boost::shared_ptr world_distance_field = - hy_world_->getCollisionWorldDistanceField()->getDistanceField(); + hy_env_->getCollisionWorldDistanceField()->getDistanceField(); if (world_distance_field->getXNumCells() != gsr_->dfce_->distance_field_->getXNumCells() || world_distance_field->getYNumCells() != gsr_->dfce_->distance_field_->getYNumCells() || world_distance_field->getZNumCells() != gsr_->dfce_->distance_field_->getZNumCells()) @@ -579,8 +576,8 @@ bool EnvironmentChain3D::setupForMotionPlan(const planning_scene::PlanningSceneC goal_state.setStateValues(goal_vals); if (!planning_parameters_.use_standard_collision_checking_) { - hy_world_->checkCollisionDistanceField(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), goal_state, - planning_scene_->getAllowedCollisionMatrix(), gsr_); + hy_env_->checkCollisionDistanceField(req, res, *hy_env_->getCollisionRobotDistanceField().get(), goal_state, + planning_scene_->getAllowedCollisionMatrix(), gsr_); } else { @@ -1101,8 +1098,8 @@ bool EnvironmentChain3D::interpolateAndCollisionCheck(const std::vector collision_detection::CollisionResult res; if (!planning_parameters_.use_standard_collision_checking_) { - hy_world_->checkCollisionDistanceField(req, res, *hy_robot_->getCollisionRobotDistanceField().get(), - interpolation_state_temp_, gsr_); + hy_env_->checkCollisionDistanceField(req, res, *hy_env_->getCollisionRobotDistanceField().get(), + interpolation_state_temp_, gsr_); } else { diff --git a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp index a2138f668d..de9a628b5a 100644 --- a/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp +++ b/moveit_ros/planning/planning_scene_monitor/src/planning_scene_monitor.cpp @@ -203,15 +203,15 @@ void PlanningSceneMonitor::initialize(const planning_scene::PlanningScenePtr& sc configureCollisionMatrix(scene_); configureDefaultPadding(); - scene_->getCollisionRobotNonConst()->setPadding(default_robot_padd_); - scene_->getCollisionRobotNonConst()->setScale(default_robot_scale_); + scene_->getCollisionEnvNonConst()->setPadding(default_robot_padd_); + scene_->getCollisionEnvNonConst()->setScale(default_robot_scale_); for (const std::pair& it : default_robot_link_padd_) { - scene_->getCollisionRobotNonConst()->setLinkPadding(it.first, it.second); + scene_->getCollisionEnvNonConst()->setLinkPadding(it.first, it.second); } for (const std::pair& it : default_robot_link_scale_) { - scene_->getCollisionRobotNonConst()->setLinkScale(it.first, it.second); + scene_->getCollisionEnvNonConst()->setLinkScale(it.first, it.second); } scene_->propogateRobotPadding(); } diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h index c212905f5f..e9a7398a90 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/include/moveit/motion_planning_rviz_plugin/motion_planning_frame.h @@ -314,7 +314,7 @@ private Q_SLOTS: ros::Publisher planning_scene_publisher_; ros::Publisher planning_scene_world_publisher_; - collision_detection::CollisionWorld::ObjectConstPtr scaled_object_; + collision_detection::CollisionEnv::ObjectConstPtr scaled_object_; std::vector > known_collision_objects_; long unsigned int known_collision_objects_version_; diff --git a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp index 9914f945de..81b7e43565 100644 --- a/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp +++ b/moveit_ros/visualization/motion_planning_rviz_plugin/src/motion_planning_frame_objects.cpp @@ -156,7 +156,7 @@ void MotionPlanningFrame::removeObjectButtonClicked() } } -static QString decideStatusText(const collision_detection::CollisionWorld::ObjectConstPtr& obj) +static QString decideStatusText(const collision_detection::CollisionEnv::ObjectConstPtr& obj) { QString status_text = "'" + QString::fromStdString(obj->id_) + "' is a collision object with "; if (obj->shapes_.empty()) @@ -228,7 +228,7 @@ void MotionPlanningFrame::selectedCollisionObjectChanged() Eigen::Isometry3d obj_pose; { const planning_scene_monitor::LockedPlanningSceneRO& ps = planning_display_->getPlanningSceneRO(); - const collision_detection::CollisionWorld::ObjectConstPtr& obj = + const collision_detection::CollisionEnv::ObjectConstPtr& obj = ps->getWorld()->getObject(sel[0]->text().toStdString()); if (obj) { @@ -302,7 +302,7 @@ void MotionPlanningFrame::updateCollisionObjectPose(bool update_marker_position) planning_scene_monitor::LockedPlanningSceneRW ps = planning_display_->getPlanningSceneRW(); if (ps) { - collision_detection::CollisionWorld::ObjectConstPtr obj = ps->getWorld()->getObject(sel[0]->text().toStdString()); + collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(sel[0]->text().toStdString()); if (obj && obj->shapes_.size() == 1) { Eigen::Isometry3d p; @@ -392,7 +392,7 @@ void MotionPlanningFrame::copySelectedCollisionObject() for (const QListWidgetItem* item : sel) { std::string name = item->text().toStdString(); - collision_detection::CollisionWorld::ObjectConstPtr obj = ps->getWorld()->getObject(name); + collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(name); if (!obj) continue; @@ -689,7 +689,7 @@ void MotionPlanningFrame::createSceneInteractiveMarker() if (!ps) return; - const collision_detection::CollisionWorld::ObjectConstPtr& obj = + const collision_detection::CollisionEnv::ObjectConstPtr& obj = ps->getWorld()->getObject(sel[0]->text().toStdString()); if (obj && obj->shapes_.size() == 1) { @@ -755,7 +755,7 @@ void MotionPlanningFrame::renameCollisionObject(QListWidgetItem* item) if (item->checkState() == Qt::Unchecked) { planning_scene_monitor::LockedPlanningSceneRW ps = planning_display_->getPlanningSceneRW(); - collision_detection::CollisionWorld::ObjectConstPtr obj = + collision_detection::CollisionEnv::ObjectConstPtr obj = ps->getWorld()->getObject(known_collision_objects_[item->type()].first); if (obj) { diff --git a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp index 85ba49b3e3..4ec1d4aa4e 100644 --- a/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp +++ b/moveit_ros/visualization/rviz_plugin_render_tools/src/planning_scene_render.cpp @@ -90,7 +90,7 @@ void PlanningSceneRender::renderPlanningScene(const planning_scene::PlanningScen const std::vector& ids = scene->getWorld()->getObjectIds(); for (const std::string& id : ids) { - collision_detection::CollisionWorld::ObjectConstPtr object = scene->getWorld()->getObject(id); + collision_detection::CollisionEnv::ObjectConstPtr object = scene->getWorld()->getObject(id); rviz::Color color = default_env_color; float alpha = default_scene_alpha; if (scene->hasObjectColor(id)) From 39171c81f53a5ef8253c8e319cb760a0cc4727ce Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Wed, 21 Aug 2019 19:10:52 +0200 Subject: [PATCH 45/96] Cleanup launch + config files (#1631) --- moveit_ros/benchmarks/examples/demo1.yaml | 2 +- .../examples/demo_panda_all_planners.launch | 27 ++++++++++--------- .../examples/demo_panda_all_planners.yaml | 1 - .../demo_panda_all_planners_obstacles.launch | 26 +++++++++--------- 4 files changed, 29 insertions(+), 27 deletions(-) diff --git a/moveit_ros/benchmarks/examples/demo1.yaml b/moveit_ros/benchmarks/examples/demo1.yaml index 7d6e9882a2..d31a58594a 100644 --- a/moveit_ros/benchmarks/examples/demo1.yaml +++ b/moveit_ros/benchmarks/examples/demo1.yaml @@ -1,5 +1,5 @@ # This is an example configuration that loads the "Kitchen" scene from the -# local MoveIt warehouse and benchmarks the "manipulator" group in the Pick1 +# local MoveIt warehouse and benchmarks the "panda_arm" group in the Pick1 # query using the Start1 initial state (all pre-stored in the local warehouse) # Three different planners from OMPL are run a total of 50 times each, with a diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch b/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch index f0d60f6105..21b2ad58a8 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners.launch @@ -7,25 +7,26 @@ - - - - + + - - - + + + + + - - - + + + - - + + + + - diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml index 3fc13adebc..5a101151f9 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners.yaml @@ -30,4 +30,3 @@ benchmark_config: - name: stomp planners: - STOMP - diff --git a/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch b/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch index 25b0a50715..763d16e86a 100644 --- a/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch +++ b/moveit_ros/benchmarks/examples/demo_panda_all_planners_obstacles.launch @@ -7,21 +7,23 @@ - - - - + + - - - + + + + + - - - + + + - - + + + + From 06d67ab119fd7fda0e45db8a59a7554fa7d55bbb Mon Sep 17 00:00:00 2001 From: Jens P Date: Wed, 21 Aug 2019 23:04:49 +0200 Subject: [PATCH 46/96] Fix clang-tidy for unified collision environment (#1638) --- .../collision_env_distance_field.h | 4 ++-- .../collision_distance_field/collision_env_hybrid.h | 4 ++-- .../src/collision_env_distance_field.cpp | 4 ++-- .../src/collision_env_hybrid.cpp | 12 ++++++------ 4 files changed, 12 insertions(+), 12 deletions(-) diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h index f9fb4366ad..93ec59597b 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_distance_field.h @@ -64,7 +64,7 @@ class CollisionEnvDistanceField : public CollisionEnv const std::map>& link_body_decompositions = std::map>(), double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, - double size_z = DEFAULT_SIZE_Z, Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + double size_z = DEFAULT_SIZE_Z, const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, @@ -75,7 +75,7 @@ class CollisionEnvDistanceField : public CollisionEnv const std::map>& link_body_decompositions = std::map>(), double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, - double size_z = DEFAULT_SIZE_Z, Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + double size_z = DEFAULT_SIZE_Z, const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, diff --git a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h index 784623385d..6acf5da2ae 100644 --- a/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h +++ b/moveit_core/collision_distance_field/include/moveit/collision_distance_field/collision_env_hybrid.h @@ -56,7 +56,7 @@ class CollisionEnvHybrid : public collision_detection::CollisionEnvFCL const std::map>& link_body_decompositions = std::map>(), double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z, - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, @@ -66,7 +66,7 @@ class CollisionEnvHybrid : public collision_detection::CollisionEnvFCL const std::map>& link_body_decompositions = std::map>(), double size_x = DEFAULT_SIZE_X, double size_y = DEFAULT_SIZE_Y, double size_z = DEFAULT_SIZE_Z, - Eigen::Vector3d origin = Eigen::Vector3d(0, 0, 0), + const Eigen::Vector3d& origin = Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field = DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution = DEFAULT_RESOLUTION, double collision_tolerance = DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance = DEFAULT_MAX_PROPOGATION_DISTANCE, double padding = 0.0, diff --git a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp index 0c1cc66d9f..6ddac01a3f 100644 --- a/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_distance_field.cpp @@ -55,7 +55,7 @@ const std::string collision_detection::CollisionDetectorAllocatorDistanceField:: CollisionEnvDistanceField::CollisionEnvDistanceField( const robot_model::RobotModelConstPtr& robot_model, const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance, double padding, double scale) : CollisionEnv(robot_model) { @@ -73,7 +73,7 @@ CollisionEnvDistanceField::CollisionEnvDistanceField( CollisionEnvDistanceField::CollisionEnvDistanceField( const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance, double padding, double scale) : CollisionEnv(robot_model, world, padding, scale) { diff --git a/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp index 9c7928112d..7a367c012f 100644 --- a/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp +++ b/moveit_core/collision_distance_field/src/collision_env_hybrid.cpp @@ -45,24 +45,24 @@ const std::string collision_detection::CollisionDetectorAllocatorHybrid::NAME("H CollisionEnvHybrid::CollisionEnvHybrid( const robot_model::RobotModelConstPtr& robot_model, const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance, double padding, double scale) : CollisionEnvFCL(robot_model) , cenv_distance_(new collision_detection::CollisionEnvDistanceField( - robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, std::move(origin), - use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance, padding, scale)) + robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field, + resolution, collision_tolerance, max_propogation_distance, padding, scale)) { } CollisionEnvHybrid::CollisionEnvHybrid( const robot_model::RobotModelConstPtr& robot_model, const WorldPtr& world, const std::map>& link_body_decompositions, double size_x, double size_y, - double size_z, Eigen::Vector3d origin, bool use_signed_distance_field, double resolution, + double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance, double padding, double scale) : CollisionEnvFCL(robot_model, world, padding, scale) , cenv_distance_(new collision_detection::CollisionEnvDistanceField( - robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, std::move(origin), - use_signed_distance_field, resolution, collision_tolerance, max_propogation_distance, padding, scale)) + robot_model, getWorld(), link_body_decompositions, size_x, size_y, size_z, origin, use_signed_distance_field, + resolution, collision_tolerance, max_propogation_distance, padding, scale)) { } From c384470cbe67c3647a4e30ef65af77c2095d4a0a Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 22 Aug 2019 15:47:55 +0200 Subject: [PATCH 47/96] Fix clang-tidy issues in merge commit 180e2b56db095cb659dc95c7ccfaa8aeea546371 --- .../src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp index 5c6bdd4c51..6675564c6c 100644 --- a/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp +++ b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp @@ -50,12 +50,12 @@ constexpr char LOGNAME[] = "combine_predefined_poses_benchmark"; class CombinePredefinedPosesBenchmark : public BenchmarkExecutor { public: - virtual bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, + bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, std::vector& start_states, std::vector& path_constraints, std::vector& goal_constraints, std::vector& traj_constraints, - std::vector& queries) + std::vector& queries) override { // Load planning scene if (!psm_) From d6c2236653e8cbac1c1eb485ee241acb1668cf57 Mon Sep 17 00:00:00 2001 From: Jens P Date: Thu, 22 Aug 2019 19:33:58 +0200 Subject: [PATCH 48/96] Changed migration notes for new unified collision environment. (#1639) --- MIGRATION.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/MIGRATION.md b/MIGRATION.md index 7fe1098d53..fb4a5c16be 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -8,7 +8,7 @@ API changes in MoveIt releases - Moved the example package `moveit_controller_manager_example` into [moveit_tutorials](https://github.com/ros-planning/moveit_tutorials) - Requests to `get_planning_scene` service without explicitly setting "components" now return full scene - `moveit_ros_plannning` no longer depends on `moveit_ros_perception` -- `collision_robot` and `collision_world` are combined into a single `collision_env`. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. `getCollisionRobot[Unpadded] / getCollisionWorld` functions return the new combined environment and will be deprecated in the future. +- `CollisionRobot` and `CollisionWorld` are combined into a single `CollisionEnv` class. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. Consequently, `getCollisionRobot[Unpadded] / getCollisionWorld` functions are replaced through a `getCollisionEnv` in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of `CollisionRobot` and `CollisionWorld`. ## ROS Melodic From b7b4197d79328e04111647004fbae1b7483a090e Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 22 Aug 2019 17:27:40 +0200 Subject: [PATCH 49/96] fix clang-format --- .../CombinePredefinedPosesBenchmark.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp index 6675564c6c..1bd9818579 100644 --- a/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp +++ b/moveit_ros/benchmarks/src/simple_benchmarks/CombinePredefinedPosesBenchmark.cpp @@ -51,11 +51,10 @@ class CombinePredefinedPosesBenchmark : public BenchmarkExecutor { public: bool loadBenchmarkQueryData(const BenchmarkOptions& opts, moveit_msgs::PlanningScene& scene_msg, - std::vector& start_states, - std::vector& path_constraints, - std::vector& goal_constraints, - std::vector& traj_constraints, - std::vector& queries) override + std::vector& start_states, std::vector& path_constraints, + std::vector& goal_constraints, + std::vector& traj_constraints, + std::vector& queries) override { // Load planning scene if (!psm_) From e6d0f3442c39e2b6948f443ccd2e93be190c4a61 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Thu, 22 Aug 2019 10:44:55 -0700 Subject: [PATCH 50/96] fallback to using pyreadline for Window. (#1635) --- moveit_commander/bin/moveit_commander_cmdline.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/moveit_commander/bin/moveit_commander_cmdline.py b/moveit_commander/bin/moveit_commander_cmdline.py index 2dffaa7630..61a37e8898 100755 --- a/moveit_commander/bin/moveit_commander_cmdline.py +++ b/moveit_commander/bin/moveit_commander_cmdline.py @@ -4,7 +4,10 @@ import roslib import rospy -import readline +try: + import readline +except ImportError: + import pyreadline as readline # for Windows import sys import os import signal From 48c326a0badc11a54c5ab2a441436c2485ee423c Mon Sep 17 00:00:00 2001 From: Jafar Abdi Date: Tue, 27 Aug 2019 14:56:41 +0300 Subject: [PATCH 51/96] Handle the updated plan() function of MoveGroupCommander (#1640) --- moveit_commander/src/moveit_commander/interpreter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/moveit_commander/src/moveit_commander/interpreter.py b/moveit_commander/src/moveit_commander/interpreter.py index 3505e6deb5..02cc10e4d4 100644 --- a/moveit_commander/src/moveit_commander/interpreter.py +++ b/moveit_commander/src/moveit_commander/interpreter.py @@ -336,11 +336,11 @@ def execute_group_command(self, g, cmdorig): if clist[1] == "rand" or clist[1] == "random": vals = g.get_random_joint_values() g.set_joint_value_target(vals) - self._last_plan = g.plan() + self._last_plan = g.plan()[1] # The trajectory msg else: try: g.set_named_target(clist[1]) - self._last_plan = g.plan() + self._last_plan = g.plan()[1] # The trajectory msg except MoveItCommanderException as e: return (MoveGroupInfoLevel.WARN, "Planning to " + clist[1] + ": " + str(e)) except: From e2bfd7198b2c645a4baeba3f6fffb336f4399600 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Tue, 27 Aug 2019 06:21:21 -0700 Subject: [PATCH 52/96] Use `.pyd` as the output suffix for Python module on Windows. (#1637) There is no other standard way to mark this in cmake --- .../planning_interface/move_group_interface/CMakeLists.txt | 3 +++ .../planning_interface/planning_scene_interface/CMakeLists.txt | 3 +++ moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt | 3 +++ moveit_ros/planning_interface/robot_interface/CMakeLists.txt | 3 +++ 4 files changed, 12 insertions(+) diff --git a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt index 6ff6444e7a..b9a4eeaa01 100644 --- a/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/move_group_interface/CMakeLists.txt @@ -11,6 +11,9 @@ add_dependencies(${MOVEIT_LIB_NAME}_python ${catkin_EXPORTED_TARGETS}) set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_move_group_interface PREFIX "") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") +if(WIN32) + set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES SUFFIX .pyd) +endif(WIN32) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt b/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt index 11489f296c..6a3b1a3f9b 100644 --- a/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/planning_scene_interface/CMakeLists.txt @@ -9,6 +9,9 @@ set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES VERSION "${${PROJECT_ target_link_libraries(${MOVEIT_LIB_NAME}_python ${MOVEIT_LIB_NAME} ${PYTHON_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES} moveit_py_bindings_tools) set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_planning_scene_interface PREFIX "") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") +if(WIN32) + set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES SUFFIX .pyd) +endif(WIN32) install(TARGETS ${MOVEIT_LIB_NAME} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt b/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt index 1f3cb1c93b..1f82d7e4dc 100644 --- a/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt +++ b/moveit_ros/planning_interface/py_bindings_tools/CMakeLists.txt @@ -14,6 +14,9 @@ target_link_libraries(${MOVEIT_LIB_NAME}_python ${MOVEIT_LIB_NAME} ${PYTHON_LIBR set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_roscpp_initializer PREFIX "") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") +if(WIN32) + set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES SUFFIX .pyd) +endif(WIN32) install(TARGETS ${MOVEIT_LIB_NAME}_python DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) diff --git a/moveit_ros/planning_interface/robot_interface/CMakeLists.txt b/moveit_ros/planning_interface/robot_interface/CMakeLists.txt index 0c6a4a22bf..3944155fbf 100644 --- a/moveit_ros/planning_interface/robot_interface/CMakeLists.txt +++ b/moveit_ros/planning_interface/robot_interface/CMakeLists.txt @@ -6,6 +6,9 @@ target_link_libraries(${MOVEIT_LIB_NAME}_python ${PYTHON_LIBRARIES} ${catkin_LIB set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES OUTPUT_NAME _moveit_robot_interface PREFIX "") set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES LIBRARY_OUTPUT_DIRECTORY "${CATKIN_DEVEL_PREFIX}/${CATKIN_PACKAGE_PYTHON_DESTINATION}") +if(WIN32) + set_target_properties(${MOVEIT_LIB_NAME}_python PROPERTIES SUFFIX .pyd) +endif(WIN32) install(TARGETS ${MOVEIT_LIB_NAME}_python DESTINATION ${CATKIN_PACKAGE_PYTHON_DESTINATION}) From 57d4a4acd20bd6c371faf956acbba4281a31e3fe Mon Sep 17 00:00:00 2001 From: Paul Verhoeckx <43780894+PaulRuvu@users.noreply.github.com> Date: Tue, 27 Aug 2019 16:38:09 +0200 Subject: [PATCH 53/96] jog_arm: Do not wait for command msg to start spinning (#1603) * Do not wait for a message on the cartesian_command_in_topic to start spinning, but only for the message we try to smooth with the low-pass filter (JointState). This also allows the initial command to be of the JointJog type. * Do not assume the command to be Cartesian when the zero_joint_cmd_flag is set, could be a JointJog command with zero velocity as well. * Remove unused publish_delay parameter * Remove mutex from jointJogCalcs() declaration --- .../jog_arm/include/jog_arm/jog_arm_data.h | 2 +- .../jog_arm/include/jog_arm/jog_calcs.h | 5 +- .../jog_arm/src/jog_arm/jog_calcs.cpp | 82 ++++++++----------- .../jog_arm/src/jog_arm/jog_ros_interface.cpp | 3 - .../test/arm_setup/config/jog_settings.yaml | 1 - 5 files changed, 37 insertions(+), 56 deletions(-) diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h b/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h index cc8309dd62..499166c427 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h @@ -86,7 +86,7 @@ struct JogArmParameters std::string move_group_name, joint_topic, cartesian_command_in_topic, command_frame, command_out_topic, planning_frame, warning_topic, joint_command_in_topic, command_in_type, command_out_type; double linear_scale, rotational_scale, joint_scale, lower_singularity_threshold, hard_stop_singularity_threshold, - collision_proximity_threshold, low_pass_filter_coeff, publish_period, publish_delay, incoming_command_timeout, + collision_proximity_threshold, low_pass_filter_coeff, publish_period, incoming_command_timeout, joint_limit_margin, collision_check_rate; int num_halt_msgs_to_publish; bool use_gazebo, check_collisions, publish_joint_positions, publish_joint_velocities, publish_joint_accelerations; diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h index f9ba6da0c9..fcdafa529b 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h +++ b/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h @@ -62,7 +62,7 @@ class JogCalcs bool cartesianJogCalcs(geometry_msgs::TwistStamped& cmd, JogArmShared& shared_variables, pthread_mutex_t& mutex); - bool jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& shared_variables, pthread_mutex_t& mutex); + bool jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& shared_variables); // Parse the incoming joint msg for the joints of our MoveGroup bool updateJoints(); @@ -97,8 +97,7 @@ class JogCalcs trajectory_msgs::JointTrajectory& new_jt_traj, const Eigen::VectorXd& delta_theta, double singularity_scale); - trajectory_msgs::JointTrajectory composeOutgoingMessage(sensor_msgs::JointState& joint_state, - const ros::Time& stamp) const; + trajectory_msgs::JointTrajectory composeOutgoingMessage(sensor_msgs::JointState& joint_state) const; void lowPassFilterVelocities(const Eigen::VectorXd& joint_vel); diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp index 64bd635bf2..8db2351350 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp +++ b/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp @@ -66,10 +66,6 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari ros::topic::waitForMessage(parameters_.joint_topic); ROS_INFO_NAMED(LOGNAME, "Received first joint msg."); - ROS_INFO_NAMED(LOGNAME, "Waiting for first command msg."); - ros::topic::waitForMessage(parameters_.cartesian_command_in_topic); - ROS_INFO_NAMED(LOGNAME, "Received first command msg."); - resetVelocityFilters(); jt_state_.name = joint_model_group_->getVariableNames(); @@ -128,8 +124,14 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari pthread_mutex_lock(&mutex); bool zero_cartesian_cmd_flag = shared_variables.zero_cartesian_cmd_flag; bool zero_joint_cmd_flag = shared_variables.zero_joint_cmd_flag; + pthread_mutex_unlock(&mutex); + + if (zero_cartesian_cmd_flag && zero_joint_cmd_flag) + // Reset low-pass filters + resetVelocityFilters(); // Pull data from the shared variables. + pthread_mutex_lock(&mutex); incoming_jts_ = shared_variables.joints; pthread_mutex_unlock(&mutex); @@ -142,8 +144,8 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari ros::Duration(WHILE_LOOP_WAIT).sleep(); } - // Assume cartesian jogging command unless the joint command has some nonzero values - if (zero_joint_cmd_flag) + // Prioritize cartesian jogging above joint jogging + if (!zero_cartesian_cmd_flag) { pthread_mutex_lock(&mutex); cartesian_deltas = shared_variables.command_deltas; @@ -152,32 +154,41 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari if (!cartesianJogCalcs(cartesian_deltas, shared_variables, mutex)) continue; } - // If joint jogging command is not all zeros - else + else if (!zero_joint_cmd_flag) { pthread_mutex_lock(&mutex); joint_deltas = shared_variables.joint_command_deltas; pthread_mutex_unlock(&mutex); - if (!jointJogCalcs(joint_deltas, shared_variables, mutex)) + if (!jointJogCalcs(joint_deltas, shared_variables)) continue; } + else + { + original_jt_state_ = jt_state_; + outgoing_command_ = composeOutgoingMessage(jt_state_); + } - // Skip publishing if the command is stale and outgoing velocities are all nearly zero. - // (It takes some time for the low-pass velocity filters to settle at zero.) + // Halt if the command is stale or inputs are all zero, or commands were zero pthread_mutex_lock(&mutex); - bool skip_publication = - shared_variables.command_is_stale && - (std::all_of(outgoing_command_.points[0].velocities.begin(), outgoing_command_.points[0].velocities.end(), - [](double i) { return i < 0.000001; })); + bool stale_command = shared_variables.command_is_stale; pthread_mutex_unlock(&mutex); + if (stale_command || (zero_cartesian_cmd_flag && zero_joint_cmd_flag)) + { + suddenHalt(outgoing_command_); + zero_cartesian_cmd_flag = true; + zero_joint_cmd_flag = true; + } + + bool valid_nonzero_command = !zero_cartesian_cmd_flag || !zero_joint_cmd_flag; + // Send the newest target joints if (!outgoing_command_.joint_names.empty()) { pthread_mutex_lock(&mutex); - // If everything normal, share the new traj to be published. - if (!skip_publication) + // If everything normal, share the new traj to be published + if (valid_nonzero_command) { shared_variables.outgoing_command = outgoing_command_; shared_variables.ok_to_publish = true; @@ -191,7 +202,7 @@ JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_vari // Reset the velocity filters so robot doesn't jump when commands resume resetVelocityFilters(); } - // The command is stale but we are publishing num_halt_msgs_to_publish + // The command is invalid but we are publishing num_halt_msgs_to_publish else { shared_variables.outgoing_command = outgoing_command_; @@ -298,22 +309,10 @@ bool JogCalcs::cartesianJogCalcs(geometry_msgs::TwistStamped& cmd, JogArmShared& // Include a velocity estimate for velocity-controlled robots Eigen::VectorXd joint_vel(delta_theta_ / parameters_.publish_period); - // Smoothly halt if the command is stale - // Positions are set to original positions, and velocities are set to zero. - // The filters will be applied after this. - pthread_mutex_lock(&mutex); - if (shared_variables.command_is_stale) - { - joint_vel.setZero(); - jt_state_ = original_jt_state_; - } - pthread_mutex_unlock(&mutex); - lowPassFilterVelocities(joint_vel); lowPassFilterPositions(); - const ros::Time next_time = ros::Time::now() + ros::Duration(parameters_.publish_period); - outgoing_command_ = composeOutgoingMessage(jt_state_, next_time); + outgoing_command_ = composeOutgoingMessage(jt_state_); // If close to a collision or a singularity, decelerate applyVelocityScaling(shared_variables, mutex, outgoing_command_, delta_theta_, @@ -336,7 +335,7 @@ bool JogCalcs::cartesianJogCalcs(geometry_msgs::TwistStamped& cmd, JogArmShared& return true; } -bool JogCalcs::jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& shared_variables, pthread_mutex_t& mutex) +bool JogCalcs::jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& shared_variables) { // Check for nan's or |delta|>1 in the incoming command for (double velocity : cmd.velocities) @@ -360,25 +359,13 @@ bool JogCalcs::jointJogCalcs(const control_msgs::JointJog& cmd, JogArmShared& sh // Include a velocity estimate for velocity-controlled robots Eigen::VectorXd joint_vel(delta / parameters_.publish_period); - // Smoothly halt if the command is stale - // Positions are set to original positions, and velocities are set to zero. - // The filters will be applied after this. - pthread_mutex_lock(&mutex); - if (shared_variables.command_is_stale) - { - joint_vel.setZero(); - jt_state_ = original_jt_state_; - } - pthread_mutex_unlock(&mutex); - lowPassFilterVelocities(joint_vel); lowPassFilterPositions(); // update joint state with new values kinematic_state_->setVariableValues(jt_state_); - const ros::Time next_time = ros::Time::now() + ros::Duration(parameters_.publish_delay); - outgoing_command_ = composeOutgoingMessage(jt_state_, next_time); + outgoing_command_ = composeOutgoingMessage(jt_state_); // check if new joint state is valid if (!checkIfJointsWithinURDFBounds(outgoing_command_)) @@ -445,12 +432,11 @@ void JogCalcs::lowPassFilterVelocities(const Eigen::VectorXd& joint_vel) } } -trajectory_msgs::JointTrajectory JogCalcs::composeOutgoingMessage(sensor_msgs::JointState& joint_state, - const ros::Time& stamp) const +trajectory_msgs::JointTrajectory JogCalcs::composeOutgoingMessage(sensor_msgs::JointState& joint_state) const { trajectory_msgs::JointTrajectory new_jt_traj; new_jt_traj.header.frame_id = parameters_.planning_frame; - new_jt_traj.header.stamp = stamp; + new_jt_traj.header.stamp = ros::Time::now(); new_jt_traj.joint_names = joint_state.name; trajectory_msgs::JointTrajectoryPoint point; diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp b/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp index 76315b79fb..1114179b52 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp +++ b/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp @@ -87,8 +87,6 @@ JogROSInterface::JogROSInterface() // Wait for incoming topics to appear ROS_DEBUG_NAMED(LOGNAME, "Waiting for JointState topic"); ros::topic::waitForMessage(ros_parameters_.joint_topic); - ROS_DEBUG_NAMED(LOGNAME, "Waiting for Cartesian command topic"); - ros::topic::waitForMessage(ros_parameters_.cartesian_command_in_topic); // Wait for low pass filters to stabilize ROS_INFO_STREAM_NAMED(LOGNAME, "Waiting for low-pass filters to stabilize."); @@ -251,7 +249,6 @@ bool JogROSInterface::readParameters(ros::NodeHandle& n) } error += !rosparam_shortcuts::get("", n, parameter_ns + "/publish_period", ros_parameters_.publish_period); - error += !rosparam_shortcuts::get("", n, parameter_ns + "/publish_delay", ros_parameters_.publish_delay); error += !rosparam_shortcuts::get("", n, parameter_ns + "/collision_check_rate", ros_parameters_.collision_check_rate); error += !rosparam_shortcuts::get("", n, parameter_ns + "/num_halt_msgs_to_publish", diff --git a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml b/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml index d9e3ff0db3..c33b0ab748 100644 --- a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml +++ b/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml @@ -17,7 +17,6 @@ collision_proximity_threshold: 0.03 # Start decelerating when a collision is thi planning_frame: base_link # The MoveIt planning frame. Often 'base_link' low_pass_filter_coeff: 2. # Larger-> more smoothing to jog commands, but more lag. publish_period: 0.01 # 1/Nominal publish rate [seconds] -publish_delay: 0.005 # delay between calculation and execution start of command collision_check_rate: 5 # [Hz] Collision-checking can easily bog down a CPU if done too often. num_halt_msgs_to_publish: 1 # If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish # Publish boolean warnings to this topic From 0ef84b85430a514fb9c095b8085954b582e2a38c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Thu, 29 Aug 2019 17:04:25 +0200 Subject: [PATCH 54/96] Cleanup OMPL dynamic reconfigure config (#1649) * reduce minimum number of waypoints in solution to 2 There is no real reason to specify 10 here by default. So instead, allow for the bare minimum of waypoints if simple interpolation from start to end succeeds and the maximum segment length suffices. Fixes #19. * ompl dyn reconfig: clean wrongly specified levels The levels are treated as bitmasks in the reconfigure callback, so counting up in natural numbers does not serve any purpose. The respective callback ignores the values either way, so this change just simplifies reading the config. --- .../ompl/ompl_interface/cfg/OMPLDynamicReconfigure.cfg | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/moveit_planners/ompl/ompl_interface/cfg/OMPLDynamicReconfigure.cfg b/moveit_planners/ompl/ompl_interface/cfg/OMPLDynamicReconfigure.cfg index 50757b73df..e9db604e9d 100755 --- a/moveit_planners/ompl/ompl_interface/cfg/OMPLDynamicReconfigure.cfg +++ b/moveit_planners/ompl/ompl_interface/cfg/OMPLDynamicReconfigure.cfg @@ -4,10 +4,10 @@ PACKAGE = "moveit_planners_ompl" from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() -gen.add("simplify_solutions", bool_t, 1, "Flag indicating whether computed motion plans are also simplified", True) -gen.add("minimum_waypoint_count", int_t, 2, "Set the minimum number of waypoints to include in a motion plan", 10, 2, 10000) -gen.add("maximum_waypoint_distance", double_t, 3, "The maximum distance between consecutive waypoints along the solution path (0.0 means 'ignore')", 0.0, 0.0, 50.0) -gen.add("link_for_exploration_tree", str_t, 4, "Show the exploration tree for a particular link", "") -gen.add("display_random_valid_states", bool_t, 5, "Flag indicating whether random valid states are to be published", False) +gen.add("simplify_solutions", bool_t, 0, "Flag indicating whether computed motion plans are also simplified", True) +gen.add("minimum_waypoint_count", int_t, 0, "Set the minimum number of waypoints to include in a motion plan", 2, 2, 10000) +gen.add("maximum_waypoint_distance", double_t, 0, "The maximum distance between consecutive waypoints along the solution path (0.0 means 'ignore')", 0.0, 0.0, 50.0) +gen.add("link_for_exploration_tree", str_t, 0, "Show the exploration tree for a particular link", "") +gen.add("display_random_valid_states", bool_t, 0, "Flag indicating whether random valid states are to be published", False) exit(gen.generate(PACKAGE, PACKAGE, "OMPLDynamicReconfigure")) From a9f232331a8d6f7f9f6d69ab30f44672334906a2 Mon Sep 17 00:00:00 2001 From: Sean Yen Date: Fri, 30 Aug 2019 01:46:30 -0700 Subject: [PATCH 55/96] [windows] some more header inclusion and MSVC build error fixes. (#1636) * Fix header inclusion for Windows build. * replace random() with c++11 usage. --- .../chomp/chomp_motion_planner/src/chomp_optimizer.cpp | 7 +++++-- moveit_ros/benchmarks/src/BenchmarkExecutor.cpp | 4 ++++ .../include/moveit/occupancy_map_monitor/occupancy_map.h | 1 + .../include/moveit/point_containment_filter/shape_mask.h | 2 +- moveit_ros/planning/plan_execution/src/plan_execution.cpp | 2 +- moveit_ros/planning/rdf_loader/src/rdf_loader.cpp | 5 +++++ moveit_setup_assistant/src/widgets/start_screen_widget.cpp | 7 +++++++ 7 files changed, 24 insertions(+), 4 deletions(-) diff --git a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp index ae30b79aad..bd8b655928 100644 --- a/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp +++ b/moveit_planners/chomp/chomp_motion_planner/src/chomp_optimizer.cpp @@ -43,12 +43,15 @@ #include #include #include +#include namespace chomp { double getRandomDouble() { - return ((double)random() / (double)RAND_MAX); + std::default_random_engine seed; + std::uniform_real_distribution<> uniform(0.0, 1.0); + return uniform(seed); } ChompOptimizer::ChompOptimizer(ChompTrajectory* trajectory, const planning_scene::PlanningSceneConstPtr& planning_scene, @@ -607,7 +610,7 @@ void ChompOptimizer::calculateCollisionIncrements() // This is faster and guaranteed to converge, but it may take more iterations in the worst case. if (parameters_->use_stochastic_descent_) { - start_point = (int)(((double)random() / (double)RAND_MAX) * (free_vars_end_ - free_vars_start_) + free_vars_start_); + start_point = (int)(getRandomDouble() * (free_vars_end_ - free_vars_start_) + free_vars_start_); if (start_point < free_vars_start_) start_point = free_vars_start_; if (start_point > free_vars_end_) diff --git a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp index 8e15bad1c1..1f55bf7102 100644 --- a/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp +++ b/moveit_ros/benchmarks/src/BenchmarkExecutor.cpp @@ -44,7 +44,11 @@ #include #include #include +#ifndef _WIN32 #include +#else +#include +#endif using namespace moveit_ros_benchmarks; diff --git a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h index 70413b3d2c..ee98f95de5 100644 --- a/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h +++ b/moveit_ros/occupancy_map_monitor/include/moveit/occupancy_map_monitor/occupancy_map.h @@ -37,6 +37,7 @@ #pragma once #include +#include #include #include #include diff --git a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h index 2fdf49c7b7..67b1b01c7f 100644 --- a/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h +++ b/moveit_ros/perception/point_containment_filter/include/moveit/point_containment_filter/shape_mask.h @@ -105,7 +105,7 @@ class ShapeMask struct SortBodies { - bool operator()(const SeeShape& b1, const SeeShape& b2) + bool operator()(const SeeShape& b1, const SeeShape& b2) const { if (b1.volume > b2.volume) return true; diff --git a/moveit_ros/planning/plan_execution/src/plan_execution.cpp b/moveit_ros/planning/plan_execution/src/plan_execution.cpp index e3f9bb84a9..fb8ee5fae1 100644 --- a/moveit_ros/planning/plan_execution/src/plan_execution.cpp +++ b/moveit_ros/planning/plan_execution/src/plan_execution.cpp @@ -517,7 +517,7 @@ void plan_execution::PlanExecution::successfulTrajectorySegmentExecution(const E if (index < plan->plan_components_.size() && plan->plan_components_[index].trajectory_ && !plan->plan_components_[index].trajectory_->empty()) { - if (!isRemainingPathValid(*plan, std::make_pair(index, 0))) + if (!isRemainingPathValid(*plan, std::make_pair(static_cast(index), 0))) path_became_invalid_ = true; } } diff --git a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp index 11a37c9329..d4885f1fd3 100644 --- a/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp +++ b/moveit_ros/planning/rdf_loader/src/rdf_loader.cpp @@ -50,6 +50,11 @@ #include #include +#ifdef _WIN32 +#define popen _popen +#define pclose _pclose +#endif + rdf_loader::RDFLoader::RDFLoader(const std::string& robot_description) { moveit::tools::Profiler::ScopedStart prof_start; diff --git a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp index a980d61071..110ba6391a 100644 --- a/moveit_setup_assistant/src/widgets/start_screen_widget.cpp +++ b/moveit_setup_assistant/src/widgets/start_screen_widget.cpp @@ -59,6 +59,13 @@ // MoveIt #include +// chdir +#ifdef _WIN32 +#include +#else +#include +#endif + namespace moveit_setup_assistant { // Boost file system From 84db86fdf91cf8d6b8ec495d11d47970b46caaa1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Fri, 30 Aug 2019 15:31:24 +0200 Subject: [PATCH 56/96] depth_image_octomap_updater: correctly set properties of debug images (#1652) (#1653) * calculate step width independent from input depth image * Also set endianness based on the host system, as the data stems from local computation. * depth updater: streamline Image properties * depth updater: enhance readability for filtered image generation --- .../src/depth_image_octomap_updater.cpp | 41 ++++++++++--------- 1 file changed, 22 insertions(+), 19 deletions(-) diff --git a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp index 4a33d7c40a..9d1840a118 100644 --- a/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp +++ b/moveit_ros/perception/depth_image_octomap_updater/src/depth_image_octomap_updater.cpp @@ -394,33 +394,32 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::ImageConstP { sensor_msgs::Image debug_msg; debug_msg.header = depth_msg->header; - debug_msg.height = depth_msg->height; - debug_msg.width = depth_msg->width; + debug_msg.height = h; + debug_msg.width = w; + debug_msg.is_bigendian = HOST_IS_BIG_ENDIAN; debug_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1; - debug_msg.is_bigendian = depth_msg->is_bigendian; - debug_msg.step = depth_msg->step; + debug_msg.step = w * sizeof(float); debug_msg.data.resize(img_size * sizeof(float)); mesh_filter_->getModelDepth(reinterpret_cast(&debug_msg.data[0])); pub_model_depth_image_.publish(debug_msg, *info_msg); sensor_msgs::Image filtered_depth_msg; filtered_depth_msg.header = depth_msg->header; - filtered_depth_msg.height = depth_msg->height; - filtered_depth_msg.width = depth_msg->width; + filtered_depth_msg.height = h; + filtered_depth_msg.width = w; + filtered_depth_msg.is_bigendian = HOST_IS_BIG_ENDIAN; filtered_depth_msg.encoding = sensor_msgs::image_encodings::TYPE_32FC1; - filtered_depth_msg.is_bigendian = depth_msg->is_bigendian; - filtered_depth_msg.step = depth_msg->step; + filtered_depth_msg.step = w * sizeof(float); filtered_depth_msg.data.resize(img_size * sizeof(float)); - mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_depth_msg.data[0])); pub_filtered_depth_image_.publish(filtered_depth_msg, *info_msg); sensor_msgs::Image label_msg; label_msg.header = depth_msg->header; - label_msg.height = depth_msg->height; - label_msg.width = depth_msg->width; + label_msg.height = h; + label_msg.width = w; + label_msg.is_bigendian = HOST_IS_BIG_ENDIAN; label_msg.encoding = sensor_msgs::image_encodings::RGBA8; - label_msg.is_bigendian = depth_msg->is_bigendian; label_msg.step = w * sizeof(unsigned int); label_msg.data.resize(img_size * sizeof(unsigned int)); mesh_filter_->getFilteredLabels(reinterpret_cast(&label_msg.data[0])); @@ -430,22 +429,26 @@ void DepthImageOctomapUpdater::depthImageCallback(const sensor_msgs::ImageConstP if (!filtered_cloud_topic_.empty()) { - static std::vector filtered_data; sensor_msgs::Image filtered_msg; filtered_msg.header = depth_msg->header; - filtered_msg.height = depth_msg->height; - filtered_msg.width = depth_msg->width; + filtered_msg.height = h; + filtered_msg.width = w; + filtered_msg.is_bigendian = HOST_IS_BIG_ENDIAN; filtered_msg.encoding = sensor_msgs::image_encodings::TYPE_16UC1; - filtered_msg.is_bigendian = depth_msg->is_bigendian; - filtered_msg.step = depth_msg->step; + filtered_msg.step = w * sizeof(unsigned short); filtered_msg.data.resize(img_size * sizeof(unsigned short)); + + // reuse float buffer across callbacks + static std::vector filtered_data; if (filtered_data.size() < img_size) filtered_data.resize(img_size); + mesh_filter_->getFilteredDepth(reinterpret_cast(&filtered_data[0])); - unsigned short* tmp_ptr = (unsigned short*)&filtered_msg.data[0]; + unsigned short* msg_data = reinterpret_cast(&filtered_msg.data[0]); for (std::size_t i = 0; i < img_size; ++i) { - tmp_ptr[i] = (unsigned short)(filtered_data[i] * 1000 + 0.5); + // rescale depth to millimeter to work with `unsigned short` + msg_data[i] = static_cast(filtered_data[i] * 1000 + 0.5); } pub_filtered_depth_image_.publish(filtered_msg, *info_msg); } From 8fcff1db6d4eb7c04236ad532f0e54b2804a6b6f Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 31 Aug 2019 20:38:41 +0200 Subject: [PATCH 57/96] chomp: fix potential calculation (#1651) --- .../chomp_motion_planner/chomp_optimizer.h | 20 ++++++++----------- 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h index 05d6c235c4..dafda7f0b2 100644 --- a/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h +++ b/moveit_planners/chomp/chomp_motion_planner/include/chomp_motion_planner/chomp_optimizer.h @@ -84,25 +84,21 @@ class ChompOptimizer inline double getPotential(double field_distance, double radius, double clearence) { double d = field_distance - radius; - double potential = 0.0; - // three cases below: - if (d >= clearence) + if (d >= clearence) // everything is fine { - potential = 0.0; + return 0.0; } - else if (d >= 0.0) + else if (d >= 0.0) // transition phase, no collision yet { - double diff = (d - clearence); - double gradient_magnitude = diff * clearence; // (diff / clearance) - potential = 0.5 * gradient_magnitude * diff; + const double diff = (d - clearence); + const double gradient_magnitude = diff / clearence; + return 0.5 * gradient_magnitude * diff; // 0.5 * (d - clearance)^2 / clearance } - else // if d < 0.0 + else // d < 0.0: collision { - potential = -d + 0.5 * clearence; + return -d + 0.5 * clearence; // linearly increase, starting from 0.5 * clearance } - - return potential; } template void getJacobian(int trajectoryPoint, Eigen::Vector3d& collision_point_pos, std::string& jointName, From 062381c75847ab8dc68e022e8987ebf514c8484b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Michael=20G=C3=B6rner?= Date: Thu, 12 Sep 2019 10:54:56 +0200 Subject: [PATCH 58/96] Fix plot details, correcting xlabels positions and cleaning the graph (#1658) (#1668) --- .../scripts/moveit_benchmark_statistics.py | 21 +++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py b/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py index 666e64c60d..50896a037d 100755 --- a/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py +++ b/moveit_ros/benchmarks/scripts/moveit_benchmark_statistics.py @@ -343,7 +343,7 @@ def plotAttribute(cur, planners, attribute, typename): color=matplotlib.cm.hot(int(floor(i*256/numValues))), label=descriptions[i]) heights = heights + measurements[i] - xtickNames = plt.xticks([x+width/2. for x in ind], labels, rotation=30) + xtickNames = plt.xticks([x + width / 2. for x in ind], labels, rotation=30, fontsize=8, ha='right') ax.set_ylabel(attribute.replace('_',' ') + ' (%)') box = ax.get_position() ax.set_position([box.x0, box.y0, box.width * 0.8, box.height]) @@ -355,7 +355,11 @@ def plotAttribute(cur, planners, attribute, typename): measurementsPercentage = [sum(m) * 100. / len(m) for m in measurements] ind = range(len(measurements)) plt.bar(ind, measurementsPercentage, width) - xtickNames = plt.xticks([x + width / 2. for x in ind], labels, rotation=30, fontsize=8) + ### uncommenting this line will remove the term 'kConfigDefault' from the labels for OMPL Solvers. + ### Fits situations where you need more control in the plot, such as in an academic publication for example + #labels = [l.replace('kConfigDefault', '') for l in labels] + + xtickNames = plt.xticks([x + width / 2. for x in ind], labels, rotation=30, fontsize=8, ha='right') ax.set_ylabel(attribute.replace('_',' ') + ' (%)') plt.subplots_adjust(bottom=0.3) # Squish the plot into the upper 2/3 of the page. Leave room for labels else: @@ -367,19 +371,24 @@ def plotAttribute(cur, planners, attribute, typename): #xtickNames = plt.xticks(labels, rotation=30, fontsize=10) #plt.subplots_adjust(bottom=0.3) # Squish the plot into the upper 2/3 of the page. Leave room for labels - + + ### uncommenting this line will remove the term 'kConfigDefault' from the labels for OMPL Solvers. + ### Fits situations where you need more control in the plot, such as in an academic publication for example + #labels = [l.replace('kConfigDefault', '') for l in labels] + xtickNames = plt.setp(ax,xticklabels=labels) - plt.setp(xtickNames, rotation=30) + plt.setp(xtickNames, rotation=30, fontsize=8, ha='right') for tick in ax.xaxis.get_major_ticks(): # shrink the font size of the x tick labels tick.label.set_fontsize(8) plt.subplots_adjust(bottom=0.3) # Squish the plot into the upper 2/3 of the page. Leave room for labels - ax.set_xlabel('Motion planning algorithm') + ax.set_xlabel('Motion planning algorithm', fontsize=12) ax.yaxis.grid(True, linestyle='-', which='major', color='lightgrey', alpha=0.5) if max(nanCounts)>0: maxy = max([max(y) for y in measurements]) for i in range(len(labels)): x = i+width/2 if typename=='BOOLEAN' else i+1 - ax.text(x, .95*maxy, str(nanCounts[i]), horizontalalignment='center', size='small') + ### uncommenting the next line, the number of failed planning attempts will be added to each bar + # ax.text(x, .95*maxy, str(nanCounts[i]), horizontalalignment='center', size='small') plt.show() def plotProgressAttribute(cur, planners, attribute): From cbe534a72639c46212d9c6caa9ee2f4c01ccd0a0 Mon Sep 17 00:00:00 2001 From: Jens P Date: Tue, 17 Sep 2019 11:22:47 +0200 Subject: [PATCH 59/96] Migration notes for unified collision environment (#1647) --- MIGRATION.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/MIGRATION.md b/MIGRATION.md index fb4a5c16be..00cf53f4fb 100644 --- a/MIGRATION.md +++ b/MIGRATION.md @@ -8,7 +8,7 @@ API changes in MoveIt releases - Moved the example package `moveit_controller_manager_example` into [moveit_tutorials](https://github.com/ros-planning/moveit_tutorials) - Requests to `get_planning_scene` service without explicitly setting "components" now return full scene - `moveit_ros_plannning` no longer depends on `moveit_ros_perception` -- `CollisionRobot` and `CollisionWorld` are combined into a single `CollisionEnv` class. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. Consequently, `getCollisionRobot[Unpadded] / getCollisionWorld` functions are replaced through a `getCollisionEnv` in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of `CollisionRobot` and `CollisionWorld`. +- `CollisionRobot` and `CollisionWorld` are combined into a single `CollisionEnv` class. This applies for all derived collision checkers as `FCL`, `ALL_VALID`, `HYBRID` and `DISTANCE_FIELD`. Consequently, `getCollisionRobot[Unpadded] / getCollisionWorld` functions are replaced through a `getCollisionEnv` in the planning scene and return the new combined environment. This unified collision environment provides the union of all member functions of `CollisionRobot` and `CollisionWorld`. Note that calling `checkRobotCollision` of the `CollisionEnv` does not take a `CollisionRobot` as an argument anymore as it is implicitly contained in the `CollisionEnv`. ## ROS Melodic From 871f3a0ded8acad77c658ce70c76855bb4ff3292 Mon Sep 17 00:00:00 2001 From: Jens P Date: Tue, 17 Sep 2019 11:23:20 +0200 Subject: [PATCH 60/96] Adding documentation to collision detection (#1645) * Collision detection documentation from #1488 * Collision detection documentation from #1505 --- .../collision_detection/collision_common.h | 23 ++--- .../collision_detector_allocator.h | 2 +- .../moveit/collision_detection/world.h | 4 +- .../collision_common.h | 87 ++++++++++++++++--- .../collision_env_fcl.h | 10 ++- .../src/collision_common.cpp | 28 ++++-- 6 files changed, 121 insertions(+), 33 deletions(-) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h index c4ec8f25a5..2991951395 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h @@ -161,11 +161,10 @@ struct CollisionResult /** \brief Number of contacts returned */ std::size_t contact_count; - /** \brief A map returning the pairs of ids of the bodies in contact, plus information about the contacts themselves - */ + /** \brief A map returning the pairs of body ids in contact, plus their contact details */ ContactMap contacts; - /** \brief When costs are computed, the individual cost sources are */ + /** \brief These are the individual cost sources when costs are computed */ std::set cost_sources; }; @@ -196,7 +195,7 @@ struct CollisionRequest /** \brief If true, a collision cost is computed */ bool cost; - /** \brief If true, compute contacts */ + /** \brief If true, compute contacts. Otherwise only a binary collision yes/no is reported. */ bool contacts; /** \brief Overall maximum number of contacts to compute */ @@ -223,14 +222,15 @@ namespace DistanceRequestTypes { enum DistanceRequestType { - GLOBAL, /// Find the global minimum - SINGLE, /// Find the global minimum for each pair - LIMITED, /// Find a limited(max_contacts_per_body) set of contacts for a given pair - ALL /// Find all the contacts for a given pair + GLOBAL, ///< Find the global minimum + SINGLE, ///< Find the global minimum for each pair + LIMITED, ///< Find a limited(max_contacts_per_body) set of contacts for a given pair + ALL ///< Find all the contacts for a given pair }; } typedef DistanceRequestTypes::DistanceRequestType DistanceRequestType; +/** \brief Representation of a distance-reporting request */ struct DistanceRequest { DistanceRequest() @@ -263,7 +263,7 @@ struct DistanceRequest /// Indicate the type of distance request. If using type=ALL, it is /// recommended to set max_contacts_per_body to the expected number - /// of contacts per pair becaused it is uesed to reserving space. + /// of contacts per pair because it is used to reserve space. DistanceRequestType type; /// Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold) @@ -279,7 +279,7 @@ struct DistanceRequest const AllowedCollisionMatrix* acm; /// Only calculate distances for objects within this threshold to each other. - /// If set this can significantly to reduce number of queries. + /// If set, this can significantly reduce the number of queries. double distance_threshold; /// Log debug information @@ -290,6 +290,7 @@ struct DistanceRequest bool compute_gradient; }; +/** \brief Generic representation of the distance information for a pair of objects */ struct DistanceResultsData { DistanceResultsData() @@ -355,8 +356,10 @@ struct DistanceResultsData } }; +/** \brief Mapping between the names of the collision objects and the DistanceResultData. */ typedef std::map, std::vector > DistanceMap; +/** \brief Result of a distance request. */ struct DistanceResult { DistanceResult() : collision(false) diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h index f1bb41d857..cbfb39a161 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/collision_detector_allocator.h @@ -92,7 +92,7 @@ class CollisionDetectorAllocatorTemplate : public CollisionDetectorAllocator return CollisionEnvPtr(new CollisionEnvType(robot_model)); } - /** Create an allocator for FCL collision detectors */ + /** Create an allocator for collision detectors. */ static CollisionDetectorAllocatorPtr create() { return CollisionDetectorAllocatorPtr(new CollisionDetectorAllocatorType()); diff --git a/moveit_core/collision_detection/include/moveit/collision_detection/world.h b/moveit_core/collision_detection/include/moveit/collision_detection/world.h index 82b299673e..ad21d3a034 100644 --- a/moveit_core/collision_detection/include/moveit/collision_detection/world.h +++ b/moveit_core/collision_detection/include/moveit/collision_detection/world.h @@ -287,7 +287,7 @@ class World /** The objects maintained in the world */ std::map objects_; - /* observers to call when something changes */ + /** Wrapper for a callback function to call when something changes in the world */ class Observer { public: @@ -296,6 +296,8 @@ class World } ObserverCallbackFn callback_; }; + + /// All registered observers of this world representation std::vector observers_; }; } diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h index 87fd375580..c5b89cca28 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_common.h @@ -58,24 +58,29 @@ namespace collision_detection { MOVEIT_STRUCT_FORWARD(CollisionGeometryData); +/** \brief Wrapper around world, link and attached objects' geometry data. */ struct CollisionGeometryData { + /** \brief Constructor for a robot link collision geometry object. */ CollisionGeometryData(const robot_model::LinkModel* link, int index) : type(BodyTypes::ROBOT_LINK), shape_index(index) { ptr.link = link; } + /** \brief Constructor for a new collision geometry object which is attached to the robot. */ CollisionGeometryData(const robot_state::AttachedBody* ab, int index) : type(BodyTypes::ROBOT_ATTACHED), shape_index(index) { ptr.ab = ab; } + /** \brief Constructor for a new world collision geometry. */ CollisionGeometryData(const World::Object* obj, int index) : type(BodyTypes::WORLD_OBJECT), shape_index(index) { ptr.obj = obj; } + /** \brief Returns the name which is saved in the member pointed to in \e ptr. */ const std::string& getID() const { switch (type) @@ -90,6 +95,7 @@ struct CollisionGeometryData return ptr.obj->id_; } + /** \brief Returns a string of the corresponding \e type. */ std::string getTypeString() const { switch (type) @@ -104,14 +110,22 @@ struct CollisionGeometryData return "Object"; } - /** \brief Check if two CollisionGeometryData objects point to the same source object */ + /** \brief Check if two CollisionGeometryData objects point to the same source object. */ bool sameObject(const CollisionGeometryData& other) const { return type == other.type && ptr.raw == other.ptr.raw; } + /** \brief Indicates the body type of the object. */ BodyType type; + + /** \brief Multiple \e CollisionGeometryData objects construct a collision object. The collision object refers to an + * array of coordinate transformations at a certain start index. The index of the transformation of a child \e + * CollisionGeometryData object is then given by adding the parent collision object index and the \e shape_index of a + * geometry data object. */ int shape_index; + + /** \brief Points to the type of body which contains the geometry. */ union { const robot_model::LinkModel* link; @@ -121,6 +135,7 @@ struct CollisionGeometryData } ptr; }; +/** \brief Data structure which is passed to the collision callback function of the collision manager. */ struct CollisionData { CollisionData() : req_(NULL), active_components_only_(NULL), res_(NULL), acm_(NULL), done_(false) @@ -136,27 +151,29 @@ struct CollisionData { } - /// Compute \e active_components_only_ based on \e req_ + /** \brief Compute \e active_components_only_ based on the joint group specified in \e req_ */ void enableGroup(const robot_model::RobotModelConstPtr& robot_model); - /// The collision request passed by the user + /** \brief The collision request passed by the user */ const CollisionRequest* req_; - /// If the collision request includes a group name, this set contains the pointers to the link models that are - /// considered for collision; - /// If the pointer is NULL, all collisions are considered. + /** \brief If the collision request includes a group name, this set contains the pointers to the link models that + * are considered for collision. + * + * If the pointer is NULL, all collisions are considered. */ const std::set* active_components_only_; - /// The user specified response location + /** \brief The user-specified response location. */ CollisionResult* res_; - /// The user specified collision matrix (may be NULL) + /** \brief The user-specified collision matrix (may be NULL). */ const AllowedCollisionMatrix* acm_; - /// Flag indicating whether collision checking is complete + /** \brief Flag indicating whether collision checking is complete. */ bool done_; }; +/** \brief Data structure which is passed to the distance callback function of the collision manager. */ struct DistanceData { DistanceData(const DistanceRequest* req, DistanceResult* res) : req(req), res(res), done(false) @@ -166,42 +183,48 @@ struct DistanceData { } - /// Distance query request information + /** \brief Distance query request information. */ const DistanceRequest* req; - /// Distance query results information + /** \brief Distance query results information. */ DistanceResult* res; - /// Indicates if distance query is finished. + /** \brief Indicates if distance query is finished. */ bool done; }; MOVEIT_STRUCT_FORWARD(FCLGeometry); +/** \brief Bundles the \e CollisionGeometryData and FCL collision geometry representation into a single class. */ struct FCLGeometry { FCLGeometry() { } + /** \brief Constructor for a robot link. */ FCLGeometry(fcl::CollisionGeometryd* collision_geometry, const robot_model::LinkModel* link, int shape_index) : collision_geometry_(collision_geometry), collision_geometry_data_(new CollisionGeometryData(link, shape_index)) { collision_geometry_->setUserData(collision_geometry_data_.get()); } + /** \brief Constructor for an attached body. */ FCLGeometry(fcl::CollisionGeometryd* collision_geometry, const robot_state::AttachedBody* ab, int shape_index) : collision_geometry_(collision_geometry), collision_geometry_data_(new CollisionGeometryData(ab, shape_index)) { collision_geometry_->setUserData(collision_geometry_data_.get()); } + /** \brief Constructor for a world object. */ FCLGeometry(fcl::CollisionGeometryd* collision_geometry, const World::Object* obj, int shape_index) : collision_geometry_(collision_geometry), collision_geometry_data_(new CollisionGeometryData(obj, shape_index)) { collision_geometry_->setUserData(collision_geometry_data_.get()); } + /** \brief Updates the \e collision_geometry_data_ with new data while also setting the \e collision_geometry_ to the + * new data. */ template void updateCollisionGeometryData(const T* data, int shape_index, bool newType) { @@ -212,13 +235,18 @@ struct FCLGeometry collision_geometry_->setUserData(collision_geometry_data_.get()); } + /** \brief Pointer to FCL collision geometry. */ std::shared_ptr collision_geometry_; + + /** \brief Pointer to the user-defined geometry data. */ CollisionGeometryDataPtr collision_geometry_data_; }; typedef std::shared_ptr FCLCollisionObjectPtr; typedef std::shared_ptr FCLCollisionObjectConstPtr; +/** \brief A general high-level object which consists of multiple \e FCLCollisionObjects. It is the top level data + * structure which is used in the collision checking process. */ struct FCLObject { void registerTo(fcl::BroadPhaseCollisionManagerd* manager); @@ -226,33 +254,65 @@ struct FCLObject void clear(); std::vector collision_objects_; + + /** \brief Geometry data corresponding to \e collision_objects_. */ std::vector collision_geometry_; }; +/** \brief Bundles an \e FCLObject and a broadphase FCL collision manager. */ struct FCLManager { FCLObject object_; std::shared_ptr manager_; }; +/** \brief Callback function used by the FCLManager used for each pair of collision objects to +* calculate object contact information. +* +* \param o1 First FCL collision object +* \param o2 Second FCL collision object +* \data General pointer to arbitrary data which is used during the callback +* \return True terminates the distance check, false continues it to the next pair of objects */ bool collisionCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void* data); +/** \brief Callback function used by the FCLManager used for each pair of collision objects to +* calculate collisions and distances. +* +* \param o1 First FCL collision object +* \param o2 Second FCL collision object +* \data General pointer to arbitrary data which is used during the callback +* \return True terminates the collision check, false continues it to the next pair of objects */ bool distanceCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void* data, double& min_dist); +/** \brief Create new FCLGeometry object out of robot link model. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const robot_model::LinkModel* link, int shape_index); + +/** \brief Create new FCLGeometry object out of attached body. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const robot_state::AttachedBody* ab, int shape_index); + +/** \brief Create new FCLGeometry object out of a world object. + * + * A world object always consists only of a single shape, therefore we don't need the \e shape_index. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const World::Object* obj); +/** \brief Create new scaled and / or padded FCLGeometry object out of robot link model. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding, const robot_model::LinkModel* link, int shape_index); + +/** \brief Create new scaled and / or padded FCLGeometry object out of an attached body. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding, const robot_state::AttachedBody* ab, int shape_index); + +/** \brief Create new scaled and / or padded FCLGeometry object out of an world object. */ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding, const World::Object* obj); + +/** \brief Increases the counter of the caches which can trigger the cleaning of expired entries from them. */ void cleanCollisionGeometryCache(); +/** \brief Transforms an Eigen Isometry3d to FCL coordinate transformation */ inline void transform2fcl(const Eigen::Isometry3d& b, fcl::Transform3d& f) { #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) @@ -264,6 +324,7 @@ inline void transform2fcl(const Eigen::Isometry3d& b, fcl::Transform3d& f) #endif } +/** \brief Transforms an Eigen Isometry3d to FCL coordinate transformation */ inline fcl::Transform3d transform2fcl(const Eigen::Isometry3d& b) { fcl::Transform3d t; @@ -271,6 +332,7 @@ inline fcl::Transform3d transform2fcl(const Eigen::Isometry3d& b) return t; } +/** \brief Transforms an FCL contact into a MoveIt contact point. */ inline void fcl2contact(const fcl::Contactd& fc, Contact& c) { c.pos = Eigen::Vector3d(fc.pos[0], fc.pos[1], fc.pos[2]); @@ -284,6 +346,7 @@ inline void fcl2contact(const fcl::Contactd& fc, Contact& c) c.body_type_2 = cgd2->type; } +/** \brief Transforms the FCL internal representation to the MoveIt \e CostSource data structure. */ inline void fcl2costsource(const fcl::CostSourced& fcs, CostSource& cs) { cs.aabb_min[0] = fcs.aabb_min[0]; diff --git a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h index b2819a6147..8906f8155f 100644 --- a/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h +++ b/moveit_core/collision_detection_fcl/include/moveit/collision_detection_fcl/collision_env_fcl.h @@ -95,14 +95,20 @@ class CollisionEnvFCL : public CollisionEnv void setWorld(const WorldPtr& world) override; protected: - /** \brief Updates the collision objects saved in the manager to reflect a new padding or scaling of the robot links - */ + /** \brief Updates the FCL collision geometry and objects saved in the CollisionRobotFCL members to reflect a new + * padding or scaling of the robot links. + * + * It searches for the link through the pointed-to robot model of the CollisionRobot and then constructs new FCL + * collision objects and geometries depending on the changed robot model. + * + * \param links The names of the links which have been updated in the robot model */ void updatedPaddingOrScaling(const std::vector& links) override; /** \brief Bundles the different checkSelfCollision functions into a single function */ void checkSelfCollisionHelper(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, const AllowedCollisionMatrix* acm) const; + /** \brief Bundles the different checkRobotCollision functions into a single function */ void checkRobotCollisionHelper(const CollisionRequest& req, CollisionResult& res, const robot_state::RobotState& state, const AllowedCollisionMatrix* acm) const; diff --git a/moveit_core/collision_detection_fcl/src/collision_common.cpp b/moveit_core/collision_detection_fcl/src/collision_common.cpp index e977b025a2..0cf3446237 100644 --- a/moveit_core/collision_detection_fcl/src/collision_common.cpp +++ b/moveit_core/collision_detection_fcl/src/collision_common.cpp @@ -356,6 +356,9 @@ bool collisionCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, voi return cdata->done_; } +/** \brief Cache for an arbitrary type of shape. It is assigned during the execution of \e createCollisionGeometry(). + * + * Only a single cache per thread and object type is created as it is a quasi-singleton instance. */ struct FCLShapeCache { using ShapeKey = shapes::ShapeConstWeakPtr; @@ -390,7 +393,10 @@ struct FCLShapeCache static const unsigned int MAX_CLEAN_COUNT = 100; // every this many uses of the cache, a cleaning operation is // executed (this is only removal of expired entries) + /** \brief Map of weak pointers to the FCLGeometry. */ ShapeMap map_; + + /** \brief Counts cache usage and triggers clearing of cache when \m MAX_CLEAN_COUNT is exceeded. */ unsigned int clean_count_; }; @@ -624,7 +630,9 @@ bool distanceCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void return cdata->done; } -/* We template the function so we get a different cache for each of the template arguments combinations */ +/* Templated function to get a different cache for each of the template arguments combinations. + * + * The returned cache is a quasi-singleton for each thread as it is created \e thread_local. */ template FCLShapeCache& GetShapeCache() { @@ -659,6 +667,11 @@ struct IfSameType }; }; +/** \brief Templated helper function creating new collision geometry out of general object using an arbitrary bounding + * volume (BV). + * + * It assigns a thread-local cache for each type of shape and minimizes memory usage and copying through utilizing the + * cache. */ template FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const T* data, int shape_index) { @@ -839,7 +852,6 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, return FCLGeometryConstPtr(); } -///////////////////////////////////////////////////// FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, const robot_model::LinkModel* link, int shape_index) { @@ -857,6 +869,8 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, return createCollisionGeometry(shape, obj, 0); } +/** \brief Templated helper function creating new collision geometry out of general object using an arbitrary bounding + * volume (BV). This can include padding and scaling. */ template FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape, double scale, double padding, const T* data, int shape_index) @@ -901,9 +915,8 @@ void cleanCollisionGeometryCache() cache2.bumpUseCount(true); } } -} // namespace collision_detection -void collision_detection::CollisionData::enableGroup(const robot_model::RobotModelConstPtr& robot_model) +void CollisionData::enableGroup(const robot_model::RobotModelConstPtr& robot_model) { if (robot_model->hasJointModelGroup(req_->group_name)) active_components_only_ = &robot_model->getJointModelGroup(req_->group_name)->getUpdatedLinkModelsSet(); @@ -911,7 +924,7 @@ void collision_detection::CollisionData::enableGroup(const robot_model::RobotMod active_components_only_ = nullptr; } -void collision_detection::FCLObject::registerTo(fcl::BroadPhaseCollisionManagerd* manager) +void FCLObject::registerTo(fcl::BroadPhaseCollisionManagerd* manager) { std::vector collision_objects(collision_objects_.size()); for (std::size_t i = 0; i < collision_objects_.size(); ++i) @@ -920,14 +933,15 @@ void collision_detection::FCLObject::registerTo(fcl::BroadPhaseCollisionManagerd manager->registerObjects(collision_objects); } -void collision_detection::FCLObject::unregisterFrom(fcl::BroadPhaseCollisionManagerd* manager) +void FCLObject::unregisterFrom(fcl::BroadPhaseCollisionManagerd* manager) { for (auto& collision_object : collision_objects_) manager->unregisterObject(collision_object.get()); } -void collision_detection::FCLObject::clear() +void FCLObject::clear() { collision_objects_.clear(); collision_geometry_.clear(); } +} // namespace collision_detection From ff71fc44bfead147b252dccefb78bee5d894841c Mon Sep 17 00:00:00 2001 From: AndyZe Date: Thu, 19 Sep 2019 08:20:41 -0700 Subject: [PATCH 61/96] Rename jog_arm->moveit_jog_arm (#1663) * Rename jog_arm->moveit_jog_arm * Address @rhaschke's feedback * apply clang-format --- .../CMakeLists.txt | 30 +++++++++---------- .../{jog_arm => moveit_jog_arm}/README.md | 4 +-- .../config/spacenav_via_teleop_tools.yaml | 2 +- .../config/ur_simulated_config.yaml | 6 ++-- .../moveit_jog_arm}/collision_check_thread.h | 13 ++++---- .../include/moveit_jog_arm}/jog_arm_data.h | 6 ++-- .../include/moveit_jog_arm}/jog_calcs.h | 10 +++---- .../moveit_jog_arm}/jog_ros_interface.h | 14 ++++----- .../include/moveit_jog_arm}/low_pass_filter.h | 6 ++-- .../launch/spacenav_cpp.launch | 8 ++--- .../launch/spacenav_teleop_tools.launch | 8 ++--- .../{jog_arm => moveit_jog_arm}/package.xml | 4 +-- .../src}/collision_check_thread.cpp | 12 ++++---- .../src}/jog_calcs.cpp | 8 ++--- .../src}/jog_ros_interface.cpp | 10 +++---- .../src/jog_server.cpp} | 10 +++---- .../src}/low_pass_filter.cpp | 8 ++--- .../teleop_examples/spacenav_to_twist.cpp | 10 +++---- .../arm_setup/config/initial_position.yaml | 0 .../test/arm_setup/config/jog_settings.yaml | 8 ++--- .../arm_setup/launch/panda_move_group.launch | 0 .../integration/test_jog_arm_integration.py | 6 ++-- .../test/launch/jog_arm_integration_test.test | 16 +++++----- 23 files changed, 100 insertions(+), 99 deletions(-) rename moveit_experimental/{jog_arm => moveit_jog_arm}/CMakeLists.txt (57%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/README.md (91%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/config/spacenav_via_teleop_tools.yaml (93%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/config/ur_simulated_config.yaml (91%) rename moveit_experimental/{jog_arm/include/jog_arm => moveit_jog_arm/include/moveit_jog_arm}/collision_check_thread.h (84%) rename moveit_experimental/{jog_arm/include/jog_arm => moveit_jog_arm/include/moveit_jog_arm}/jog_arm_data.h (97%) rename moveit_experimental/{jog_arm/include/jog_arm => moveit_jog_arm/include/moveit_jog_arm}/jog_calcs.h (97%) rename moveit_experimental/{jog_arm/include/jog_arm => moveit_jog_arm/include/moveit_jog_arm}/jog_ros_interface.h (93%) rename moveit_experimental/{jog_arm/include/jog_arm => moveit_jog_arm/include/moveit_jog_arm}/low_pass_filter.h (96%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/launch/spacenav_cpp.launch (65%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/launch/spacenav_teleop_tools.launch (72%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/package.xml (89%) rename moveit_experimental/{jog_arm/src/jog_arm => moveit_jog_arm/src}/collision_check_thread.cpp (94%) rename moveit_experimental/{jog_arm/src/jog_arm => moveit_jog_arm/src}/jog_calcs.cpp (99%) rename moveit_experimental/{jog_arm/src/jog_arm => moveit_jog_arm/src}/jog_ros_interface.cpp (98%) rename moveit_experimental/{jog_arm/src/jog_arm/jog_arm_server.cpp => moveit_jog_arm/src/jog_server.cpp} (89%) rename moveit_experimental/{jog_arm/src/jog_arm => moveit_jog_arm/src}/low_pass_filter.cpp (95%) rename moveit_experimental/{jog_arm/src/jog_arm => moveit_jog_arm/src}/teleop_examples/spacenav_to_twist.cpp (91%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/test/arm_setup/config/initial_position.yaml (100%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/test/arm_setup/config/jog_settings.yaml (86%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/test/arm_setup/launch/panda_move_group.launch (100%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/test/integration/test_jog_arm_integration.py (93%) rename moveit_experimental/{jog_arm => moveit_jog_arm}/test/launch/jog_arm_integration_test.test (58%) diff --git a/moveit_experimental/jog_arm/CMakeLists.txt b/moveit_experimental/moveit_jog_arm/CMakeLists.txt similarity index 57% rename from moveit_experimental/jog_arm/CMakeLists.txt rename to moveit_experimental/moveit_jog_arm/CMakeLists.txt index 733d4dd328..e95c156c6b 100644 --- a/moveit_experimental/jog_arm/CMakeLists.txt +++ b/moveit_experimental/moveit_jog_arm/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(jog_arm) +project(moveit_jog_arm) add_compile_options(-std=c++11) @@ -37,27 +37,27 @@ include_directories( ${EIGEN3_INCLUDE_DIRS} ) -add_executable(${PROJECT_NAME}_server - src/jog_arm/collision_check_thread.cpp - src/jog_arm/jog_arm_server.cpp - src/jog_arm/jog_calcs.cpp - src/jog_arm/jog_ros_interface.cpp - src/jog_arm/low_pass_filter.cpp +add_executable(jog_server + src/collision_check_thread.cpp + src/jog_server.cpp + src/jog_calcs.cpp + src/jog_ros_interface.cpp + src/low_pass_filter.cpp ) -add_dependencies(${PROJECT_NAME}_server ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${PROJECT_NAME}_server ${catkin_LIBRARIES} ${Eigen_LIBRARIES}) +add_dependencies(jog_server ${catkin_EXPORTED_TARGETS}) +target_link_libraries(jog_server ${catkin_LIBRARIES} ${Eigen_LIBRARIES}) -add_executable(${PROJECT_NAME}_spacenav_to_twist - src/jog_arm/teleop_examples/spacenav_to_twist.cpp +add_executable(spacenav_to_twist + src/teleop_examples/spacenav_to_twist.cpp ) -add_dependencies(${PROJECT_NAME}_spacenav_to_twist ${catkin_EXPORTED_TARGETS}) -target_link_libraries(${PROJECT_NAME}_spacenav_to_twist ${catkin_LIBRARIES}) +add_dependencies(spacenav_to_twist ${catkin_EXPORTED_TARGETS}) +target_link_libraries(spacenav_to_twist ${catkin_LIBRARIES}) install( TARGETS - ${PROJECT_NAME}_server - ${PROJECT_NAME}_spacenav_to_twist + jog_server + spacenav_to_twist RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) diff --git a/moveit_experimental/jog_arm/README.md b/moveit_experimental/moveit_jog_arm/README.md similarity index 91% rename from moveit_experimental/jog_arm/README.md rename to moveit_experimental/moveit_jog_arm/README.md index af983f78d6..0543aed922 100644 --- a/moveit_experimental/jog_arm/README.md +++ b/moveit_experimental/moveit_jog_arm/README.md @@ -32,12 +32,12 @@ strictness: 2" Launch the jog node. This example uses commands from a SpaceNavigator joystick-like device: - roslaunch jog_arm spacenav_cpp.launch + roslaunch moveit_jog_arm spacenav_cpp.launch If you dont have a SpaceNavigator, send commands like this: ```sh -rostopic pub -r 100 /jog_arm_server/delta_jog_cmds geometry_msgs/TwistStamped "header: auto +rostopic pub -r 100 /jog_server/delta_jog_cmds geometry_msgs/TwistStamped "header: auto twist: linear: x: 0.0 diff --git a/moveit_experimental/jog_arm/config/spacenav_via_teleop_tools.yaml b/moveit_experimental/moveit_jog_arm/config/spacenav_via_teleop_tools.yaml similarity index 93% rename from moveit_experimental/jog_arm/config/spacenav_via_teleop_tools.yaml rename to moveit_experimental/moveit_jog_arm/config/spacenav_via_teleop_tools.yaml index cd9e53c9df..2308e0c5a0 100644 --- a/moveit_experimental/jog_arm/config/spacenav_via_teleop_tools.yaml +++ b/moveit_experimental/moveit_jog_arm/config/spacenav_via_teleop_tools.yaml @@ -2,7 +2,7 @@ teleop: cartesian_twist_command: type: topic message_type: geometry_msgs/TwistStamped - topic_name: jog_arm_server/delta_jog_cmds + topic_name: jog_server/delta_jog_cmds axis_mappings: - axis: 0 diff --git a/moveit_experimental/jog_arm/config/ur_simulated_config.yaml b/moveit_experimental/moveit_jog_arm/config/ur_simulated_config.yaml similarity index 91% rename from moveit_experimental/jog_arm/config/ur_simulated_config.yaml rename to moveit_experimental/moveit_jog_arm/config/ur_simulated_config.yaml index 8e6d32fb73..839a4b16a5 100644 --- a/moveit_experimental/jog_arm/config/ur_simulated_config.yaml +++ b/moveit_experimental/moveit_jog_arm/config/ur_simulated_config.yaml @@ -42,10 +42,10 @@ hard_stop_singularity_threshold: 30 # Stop when the condition number hits this joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. ## Topic names -cartesian_command_in_topic: jog_arm_server/delta_jog_cmds # Topic for incoming Cartesian twist commands -joint_command_in_topic: jog_arm_server/joint_delta_jog_cmds # Topic for incoming joint angle commands +cartesian_command_in_topic: jog_server/delta_jog_cmds # Topic for incoming Cartesian twist commands +joint_command_in_topic: jog_server/joint_delta_jog_cmds # Topic for incoming joint angle commands joint_topic: joint_states -warning_topic: jog_arm_server/halted # Publish boolean warnings to this topic +warning_topic: jog_server/halted # Publish boolean warnings to this topic command_out_topic: joint_group_position_controller/command # Publish outgoing commands here ## Collision checking diff --git a/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/collision_check_thread.h similarity index 84% rename from moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h rename to moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/collision_check_thread.h index 4b3680b5f3..d5c8551576 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/collision_check_thread.h +++ b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/collision_check_thread.h @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : collision_check_thread.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -39,17 +39,18 @@ #pragma once -#include -#include +#include "jog_arm_data.h" +#include "low_pass_filter.h" #include #include -namespace jog_arm +namespace moveit_jog_arm { class CollisionCheckThread { public: - CollisionCheckThread(const jog_arm::JogArmParameters parameters, jog_arm::JogArmShared& shared_variables, - pthread_mutex_t& mutex, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr); + CollisionCheckThread(const moveit_jog_arm::JogArmParameters parameters, + moveit_jog_arm::JogArmShared& shared_variables, pthread_mutex_t& mutex, + const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr); }; } diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_arm_data.h similarity index 97% rename from moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h rename to moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_arm_data.h index 499166c427..0950d07405 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_arm_data.h +++ b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_arm_data.h @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : jog_arm_data.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -45,9 +45,9 @@ #include #include -namespace jog_arm +namespace moveit_jog_arm { -static const std::string LOGNAME = "jog_arm_server"; +static const std::string LOGNAME = "jog_server"; static const double WHILE_LOOP_WAIT = 0.001; // Variables to share between threads, and their mutexes diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_calcs.h similarity index 97% rename from moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h rename to moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_calcs.h index fcdafa529b..4d01690c7a 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_calcs.h +++ b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_calcs.h @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : jog_calcs.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -39,15 +39,15 @@ #pragma once -#include -#include +#include "jog_arm_data.h" +#include "low_pass_filter.h" #include #include #include #include #include -namespace jog_arm +namespace moveit_jog_arm { class JogCalcs { @@ -132,4 +132,4 @@ class JogCalcs uint num_joints_; }; -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_ros_interface.h similarity index 93% rename from moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h rename to moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_ros_interface.h index ef5f7d8d66..8d69686430 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/jog_ros_interface.h +++ b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/jog_ros_interface.h @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : jog_ros_interface.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 3/9/2017 // Author : Brian O'Neil, Blake Anderson, Andy Zelenak // @@ -41,17 +41,17 @@ #pragma once +#include "collision_check_thread.h" #include -#include -#include -#include -#include +#include "jog_arm_data.h" +#include "jog_calcs.h" +#include "low_pass_filter.h" #include #include #include #include -namespace jog_arm +namespace moveit_jog_arm { /** * Class JogROSInterface - Instantiated in main(). Handles ROS subs & pubs and creates the worker threads. @@ -85,4 +85,4 @@ class JogROSInterface // Store the parameters that were read from ROS server JogArmParameters ros_parameters_; }; -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/low_pass_filter.h similarity index 96% rename from moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h rename to moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/low_pass_filter.h index d1a3e937db..424ab6e2f1 100644 --- a/moveit_experimental/jog_arm/include/jog_arm/low_pass_filter.h +++ b/moveit_experimental/moveit_jog_arm/include/moveit_jog_arm/low_pass_filter.h @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : low_pass_filter.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Andy Zelenak // @@ -39,7 +39,7 @@ #pragma once -namespace jog_arm +namespace moveit_jog_arm { /** * Class LowPassFilter - Filter a signal to soften jerks. @@ -62,4 +62,4 @@ class LowPassFilter // https://www.wolframalpha.com/input/?i=plot+arccot(c) double filter_coeff_ = 10.; }; -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/launch/spacenav_cpp.launch b/moveit_experimental/moveit_jog_arm/launch/spacenav_cpp.launch similarity index 65% rename from moveit_experimental/jog_arm/launch/spacenav_cpp.launch rename to moveit_experimental/moveit_jog_arm/launch/spacenav_cpp.launch index 4b5b023842..c78dff5b6b 100644 --- a/moveit_experimental/jog_arm/launch/spacenav_cpp.launch +++ b/moveit_experimental/moveit_jog_arm/launch/spacenav_cpp.launch @@ -10,11 +10,11 @@ - + - - - + + + diff --git a/moveit_experimental/jog_arm/launch/spacenav_teleop_tools.launch b/moveit_experimental/moveit_jog_arm/launch/spacenav_teleop_tools.launch similarity index 72% rename from moveit_experimental/jog_arm/launch/spacenav_teleop_tools.launch rename to moveit_experimental/moveit_jog_arm/launch/spacenav_teleop_tools.launch index 5df96be11b..6b3a97cf92 100644 --- a/moveit_experimental/jog_arm/launch/spacenav_teleop_tools.launch +++ b/moveit_experimental/moveit_jog_arm/launch/spacenav_teleop_tools.launch @@ -9,14 +9,14 @@ - - - + + + - + diff --git a/moveit_experimental/jog_arm/package.xml b/moveit_experimental/moveit_jog_arm/package.xml similarity index 89% rename from moveit_experimental/jog_arm/package.xml rename to moveit_experimental/moveit_jog_arm/package.xml index 6bf404a71d..ed1227fce6 100644 --- a/moveit_experimental/jog_arm/package.xml +++ b/moveit_experimental/moveit_jog_arm/package.xml @@ -1,6 +1,6 @@ - jog_arm + moveit_jog_arm 0.0.3 Provides real-time manipulator Cartesian jogging. @@ -10,7 +10,7 @@ BSD 3-Clause - http://wiki.ros.org/jog_arm + https://ros-planning.github.io/moveit_tutorials Brian O'Neil Andy Zelenak diff --git a/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp b/moveit_experimental/moveit_jog_arm/src/collision_check_thread.cpp similarity index 94% rename from moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp rename to moveit_experimental/moveit_jog_arm/src/collision_check_thread.cpp index 3b165a3e95..56cb82d164 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/collision_check_thread.cpp +++ b/moveit_experimental/moveit_jog_arm/src/collision_check_thread.cpp @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : collision_check_thread.cpp -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -37,13 +37,13 @@ // /////////////////////////////////////////////////////////////////////////////// -#include +#include -namespace jog_arm +namespace moveit_jog_arm { // Constructor for the class that handles collision checking -CollisionCheckThread::CollisionCheckThread(const jog_arm::JogArmParameters parameters, JogArmShared& shared_variables, - pthread_mutex_t& mutex, +CollisionCheckThread::CollisionCheckThread(const moveit_jog_arm::JogArmParameters parameters, + JogArmShared& shared_variables, pthread_mutex_t& mutex, const robot_model_loader::RobotModelLoaderPtr& model_loader_ptr) { // If user specified true in yaml file @@ -134,4 +134,4 @@ CollisionCheckThread::CollisionCheckThread(const jog_arm::JogArmParameters param } } } -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp b/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp similarity index 99% rename from moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp rename to moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp index 8db2351350..b90cd6fd70 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_calcs.cpp +++ b/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : jog_calcs.h -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -37,9 +37,9 @@ // /////////////////////////////////////////////////////////////////////////////// -#include +#include -namespace jog_arm +namespace moveit_jog_arm { // Constructor for the class that handles jogging calculations JogCalcs::JogCalcs(const JogArmParameters& parameters, JogArmShared& shared_variables, pthread_mutex_t& mutex, @@ -762,4 +762,4 @@ bool JogCalcs::addJointIncrements(sensor_msgs::JointState& output, const Eigen:: return true; } -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp b/moveit_experimental/moveit_jog_arm/src/jog_ros_interface.cpp similarity index 98% rename from moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp rename to moveit_experimental/moveit_jog_arm/src/jog_ros_interface.cpp index 1114179b52..6eea959af4 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_ros_interface.cpp +++ b/moveit_experimental/moveit_jog_arm/src/jog_ros_interface.cpp @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : jog_ros_interface.cpp -// Project : jog_arm +// Project : moveit_jog_arm // Created : 3/9/2017 // Author : Brian O'Neil, Andy Zelenak, Blake Anderson // @@ -39,9 +39,9 @@ // Server node for arm jogging with MoveIt. -#include +#include -namespace jog_arm +namespace moveit_jog_arm { ///////////////////////////////////////////////////////////////////////////////// // JogROSInterface handles ROS subscriptions and instantiates the worker threads. @@ -244,7 +244,7 @@ bool JogROSInterface::readParameters(ros::NodeHandle& n) ROS_ERROR_STREAM_NAMED(LOGNAME, "A namespace must be specified in the launch file, like:"); ROS_ERROR_STREAM_NAMED(LOGNAME, ""); + "value=\"left_jog_server\" />"); return false; } @@ -367,4 +367,4 @@ bool JogROSInterface::readParameters(ros::NodeHandle& n) return true; } -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/src/jog_arm/jog_arm_server.cpp b/moveit_experimental/moveit_jog_arm/src/jog_server.cpp similarity index 89% rename from moveit_experimental/jog_arm/src/jog_arm/jog_arm_server.cpp rename to moveit_experimental/moveit_jog_arm/src/jog_server.cpp index 2d2c545a70..ba96f3049f 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/jog_arm_server.cpp +++ b/moveit_experimental/moveit_jog_arm/src/jog_server.cpp @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// -// Title : jog_arm_server.cpp -// Project : jog_arm +// Title : jog_server.cpp +// Project : moveit_jog_arm // Created : 12/31/2018 // Author : Andy Zelenak // @@ -37,13 +37,13 @@ // /////////////////////////////////////////////////////////////////////////////// -#include +#include int main(int argc, char** argv) { - ros::init(argc, argv, jog_arm::LOGNAME); + ros::init(argc, argv, moveit_jog_arm::LOGNAME); - jog_arm::JogROSInterface ros_interface; + moveit_jog_arm::JogROSInterface ros_interface; return 0; } diff --git a/moveit_experimental/jog_arm/src/jog_arm/low_pass_filter.cpp b/moveit_experimental/moveit_jog_arm/src/low_pass_filter.cpp similarity index 95% rename from moveit_experimental/jog_arm/src/jog_arm/low_pass_filter.cpp rename to moveit_experimental/moveit_jog_arm/src/low_pass_filter.cpp index 719011f9e1..8ee2809a5c 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/low_pass_filter.cpp +++ b/moveit_experimental/moveit_jog_arm/src/low_pass_filter.cpp @@ -1,6 +1,6 @@ /////////////////////////////////////////////////////////////////////////////// // Title : low_pass_filter.cpp -// Project : jog_arm +// Project : moveit_jog_arm // Created : 1/11/2019 // Author : Andy Zelenak // @@ -37,9 +37,9 @@ // /////////////////////////////////////////////////////////////////////////////// -#include +#include -namespace jog_arm +namespace moveit_jog_arm { LowPassFilter::LowPassFilter(double low_pass_filter_coeff) { @@ -68,4 +68,4 @@ double LowPassFilter::filter(double new_measurement) return new_filtered_msrmt; } -} // namespace jog_arm +} // namespace moveit_jog_arm diff --git a/moveit_experimental/jog_arm/src/jog_arm/teleop_examples/spacenav_to_twist.cpp b/moveit_experimental/moveit_jog_arm/src/teleop_examples/spacenav_to_twist.cpp similarity index 91% rename from moveit_experimental/jog_arm/src/jog_arm/teleop_examples/spacenav_to_twist.cpp rename to moveit_experimental/moveit_jog_arm/src/teleop_examples/spacenav_to_twist.cpp index f795d07529..20ca24a382 100644 --- a/moveit_experimental/jog_arm/src/jog_arm/teleop_examples/spacenav_to_twist.cpp +++ b/moveit_experimental/moveit_jog_arm/src/teleop_examples/spacenav_to_twist.cpp @@ -3,7 +3,7 @@ #include "ros/ros.h" #include "sensor_msgs/Joy.h" -namespace jog_arm +namespace moveit_jog_arm { static const int NUM_SPINNERS = 1; static const int QUEUE_LENGTH = 1; @@ -14,8 +14,8 @@ class SpaceNavToTwist SpaceNavToTwist() : spinner_(NUM_SPINNERS) { joy_sub_ = n_.subscribe("spacenav/joy", QUEUE_LENGTH, &SpaceNavToTwist::joyCallback, this); - twist_pub_ = n_.advertise("jog_arm_server/delta_jog_cmds", QUEUE_LENGTH); - joint_delta_pub_ = n_.advertise("jog_arm_server/joint_delta_jog_cmds", QUEUE_LENGTH); + twist_pub_ = n_.advertise("jog_server/delta_jog_cmds", QUEUE_LENGTH); + joint_delta_pub_ = n_.advertise("jog_server/joint_delta_jog_cmds", QUEUE_LENGTH); spinner_.start(); ros::waitForShutdown(); @@ -57,13 +57,13 @@ class SpaceNavToTwist ros::Publisher twist_pub_, joint_delta_pub_; ros::AsyncSpinner spinner_; }; -} // namespace jog_arm +} // namespace moveit_jog_arm int main(int argc, char** argv) { ros::init(argc, argv, "spacenav_to_twist"); - jog_arm::SpaceNavToTwist to_twist; + moveit_jog_arm::SpaceNavToTwist to_twist; return 0; } diff --git a/moveit_experimental/jog_arm/test/arm_setup/config/initial_position.yaml b/moveit_experimental/moveit_jog_arm/test/arm_setup/config/initial_position.yaml similarity index 100% rename from moveit_experimental/jog_arm/test/arm_setup/config/initial_position.yaml rename to moveit_experimental/moveit_jog_arm/test/arm_setup/config/initial_position.yaml diff --git a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml b/moveit_experimental/moveit_jog_arm/test/arm_setup/config/jog_settings.yaml similarity index 86% rename from moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml rename to moveit_experimental/moveit_jog_arm/test/arm_setup/config/jog_settings.yaml index c33b0ab748..6fd1119af4 100644 --- a/moveit_experimental/jog_arm/test/arm_setup/config/jog_settings.yaml +++ b/moveit_experimental/moveit_jog_arm/test/arm_setup/config/jog_settings.yaml @@ -5,8 +5,8 @@ scale: # Only used if command_in_type=="unitless" linear: 0.003 # Max linear velocity. Meters per publish_period. rotational: 0.006 # Max angular velocity. Rads per publish_period. joint: 0.01 # Max joint angular/linear velocity. Rads or Meters per publish period. -cartesian_command_in_topic: jog_arm_server/delta_jog_cmds # Topic for xyz commands -joint_command_in_topic: jog_arm_server/joint_delta_jog_cmds # Topic for angle commands +cartesian_command_in_topic: jog_server/delta_jog_cmds # Topic for xyz commands +joint_command_in_topic: jog_server/joint_delta_jog_cmds # Topic for angle commands command_frame: base_link # TF frame that incoming cmds are given in incoming_command_timeout: 1 # Stop jogging if X seconds elapsed without a new cmd joint_topic: joint_states @@ -20,9 +20,9 @@ publish_period: 0.01 # 1/Nominal publish rate [seconds] collision_check_rate: 5 # [Hz] Collision-checking can easily bog down a CPU if done too often. num_halt_msgs_to_publish: 1 # If 0, republish commands forever even if the robot is stationary. Otherwise, specify num. to publish # Publish boolean warnings to this topic -warning_topic: jog_arm_server/warning +warning_topic: jog_server/warning joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger. -command_out_topic: jog_arm_server/command # Find this topic by 'rostopic list' or 'rostopic list | grep command' or 'rqt_graph' +command_out_topic: jog_server/command # Find this topic by 'rostopic list' or 'rostopic list | grep command' or 'rqt_graph' # What type of topic does your robot driver expect? # Currently supported are std_msgs/Float64MultiArray (for ros_control JointGroupVelocityController) # or trajectory_msgs/JointTrajectory (for Universal Robots and other non-ros_control robots) diff --git a/moveit_experimental/jog_arm/test/arm_setup/launch/panda_move_group.launch b/moveit_experimental/moveit_jog_arm/test/arm_setup/launch/panda_move_group.launch similarity index 100% rename from moveit_experimental/jog_arm/test/arm_setup/launch/panda_move_group.launch rename to moveit_experimental/moveit_jog_arm/test/arm_setup/launch/panda_move_group.launch diff --git a/moveit_experimental/jog_arm/test/integration/test_jog_arm_integration.py b/moveit_experimental/moveit_jog_arm/test/integration/test_jog_arm_integration.py similarity index 93% rename from moveit_experimental/jog_arm/test/integration/test_jog_arm_integration.py rename to moveit_experimental/moveit_jog_arm/test/integration/test_jog_arm_integration.py index 6689c0224a..ca30f5f3ed 100755 --- a/moveit_experimental/jog_arm/test/integration/test_jog_arm_integration.py +++ b/moveit_experimental/moveit_jog_arm/test/integration/test_jog_arm_integration.py @@ -11,10 +11,10 @@ JOG_ARM_SETTLE_TIME_S = 10 ROS_SETTLE_TIME_S = 10 -JOINT_JOG_COMMAND_TOPIC = 'jog_arm_server/joint_delta_jog_cmds' -CARTESIAN_JOG_COMMAND_TOPIC = 'jog_arm_server/delta_jog_cmds' +JOINT_JOG_COMMAND_TOPIC = 'jog_server/joint_delta_jog_cmds' +CARTESIAN_JOG_COMMAND_TOPIC = 'jog_server/delta_jog_cmds' -COMMAND_OUT_TOPIC = 'jog_arm_server/command' +COMMAND_OUT_TOPIC = 'jog_server/command' @pytest.fixture diff --git a/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test b/moveit_experimental/moveit_jog_arm/test/launch/jog_arm_integration_test.test similarity index 58% rename from moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test rename to moveit_experimental/moveit_jog_arm/test/launch/jog_arm_integration_test.test index 8845fd0815..4cd7ccb4c2 100644 --- a/moveit_experimental/jog_arm/test/launch/jog_arm_integration_test.test +++ b/moveit_experimental/moveit_jog_arm/test/launch/jog_arm_integration_test.test @@ -10,7 +10,7 @@ These aren't suitable for actually jogging a robot in RViz, but they are good enough to test jog node output. --> - + @@ -19,20 +19,20 @@ - + - - + + - - - + + + - + From ff8f1d8503d907789acca7ef3a84f8c361bd8749 Mon Sep 17 00:00:00 2001 From: Henning Kayser Date: Thu, 19 Sep 2019 19:32:25 +0200 Subject: [PATCH 62/96] Fix double mutex unlock (#1672) --- moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp b/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp index b90cd6fd70..0ff378a533 100644 --- a/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp +++ b/moveit_experimental/moveit_jog_arm/src/jog_calcs.cpp @@ -465,7 +465,7 @@ bool JogCalcs::applyVelocityScaling(JogArmShared& shared_variables, pthread_mute trajectory_msgs::JointTrajectory& new_jt_traj, const Eigen::VectorXd& delta_theta, double singularity_scale) { - pthread_mutex_unlock(&mutex); + pthread_mutex_lock(&mutex); double collision_scale = shared_variables.collision_velocity_scale; pthread_mutex_unlock(&mutex); From 981502382050651621829eb0ad1e945deb4c6520 Mon Sep 17 00:00:00 2001 From: Omid Heidari Date: Tue, 11 Jun 2019 18:51:26 -0600 Subject: [PATCH 63/96] TrajOpt Planner (Empty Template) (#1478) * Created EmptyPlan, a MoveIt planning plugin template * added trajopt from example_planner * fixed trajopt_planner_mannager * modified emaptyplan_planner_manager.cpp * applied Dave's modifications * The rest of the modifications from Dave's comments * removed moveit_ros_planning dependency from package.xml * fixed clangformat error and dependency issu * added include directory * edited package.xml * added include * remove include * remove version_gte from package.xml * updated the setup assitant to work with trajopt planner * removed unsuded part in initialize() from trajopt_planner_manager.cpp, kept the initialize() itself for later use * Update moveit_planners/trajopt/src/trajopt_planner_manager.cpp Co-Authored-By: Dave Coleman * added README added description to trajopt_interface_plugin_description.xml --- moveit_planners/trajopt/CMakeLists.txt | 29 +++++++++++++++++++ .../widgets/configuration_files_widget.cpp | 21 ++++++++++++++ 2 files changed, 50 insertions(+) diff --git a/moveit_planners/trajopt/CMakeLists.txt b/moveit_planners/trajopt/CMakeLists.txt index f93e000d34..344c2b0c31 100644 --- a/moveit_planners/trajopt/CMakeLists.txt +++ b/moveit_planners/trajopt/CMakeLists.txt @@ -7,6 +7,7 @@ if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE Release) endif() +<<<<<<< HEAD find_package(catkin REQUIRED COMPONENTS moveit_core @@ -62,10 +63,28 @@ set_target_properties( VERSION "${${PROJECT_NAME}_VERSION}" ) +======= +find_package(catkin REQUIRED COMPONENTS + moveit_core + roscpp + pluginlib +) + +catkin_package( + CATKIN_DEPENDS + moveit_core +) + +# The following include_directory should have include folder of the new planner. +include_directories(${Boost_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ${TrajOpt_INCLUDE_DIRS}) +>>>>>>> TrajOpt Planner (Empty Template) (#1478) # TrajOpt planning plugin add_library(moveit_trajopt_planner_plugin src/trajopt_planner_manager.cpp) set_target_properties(moveit_trajopt_planner_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") +<<<<<<< HEAD target_link_libraries(moveit_trajopt_planner_plugin ${PROJECT_NAME} ${catkin_LIBRARIES}) ############# @@ -111,3 +130,13 @@ if(CATKIN_ENABLE_TESTING) ) endif() +======= + +install(TARGETS + moveit_trajopt_planner_plugin + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) + +install(FILES trajopt_interface_plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) +>>>>>>> TrajOpt Planner (Empty Template) (#1478) diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index 5356e9801b..a2b9e1f03b 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -374,6 +374,18 @@ bool ConfigurationFilesWidget::loadGenFiles() file.write_on_changes = 0; gen_files_.push_back(file); + // trajopt_planning_pipeline.launch + // -------------------------------------------------------------------------------------- + file.file_name_ = "trajopt_planning_pipeline.launch.xml"; + file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); + template_path = config_data_->appendPaths(template_launch_path, file.file_name_); + file.description_ = "Intended to be included in other launch files that require the TrajOpt planning plugin. Defines " + "the proper plugin name on the parameter server and a default selection of planning request " + "adapters."; + file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.write_on_changes = 0; + gen_files_.push_back(file); + // chomp_planning_pipeline.launch // -------------------------------------------------------------------------------------- file.file_name_ = "chomp_planning_pipeline.launch.xml"; @@ -431,6 +443,15 @@ bool ConfigurationFilesWidget::loadGenFiles() file.write_on_changes = 0; gen_files_.push_back(file); + // run_benchmark_trajopt.launch -------------------------------------------------------------------------------------- + file.file_name_ = "run_benchmark_trajopt.launch"; + file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); + template_path = config_data_->appendPaths(template_launch_path, file.file_name_); + file.description_ = "Launch file for benchmarking TrajOpt planners"; + file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); + file.write_on_changes = 0; + gen_files_.push_back(file); + // sensor_manager.launch -------------------------------------------------------------------------------------- file.file_name_ = "sensor_manager.launch.xml"; file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); From 0c7664af302868287d3948288e1ba73d0198135b Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 6 Jun 2019 19:31:17 -0600 Subject: [PATCH 64/96] added solve from tesseract. added launch file improved test_trajopt node edited package.xml --- moveit_planners/trajopt/config/setup.yaml | 0 .../include/trajopt_planning_context.h | 84 +++++++ .../trajopt/launch/gdb_settings.gdb | 8 + .../trajopt/launch/test_trajopt_launch.launch | 27 ++ moveit_planners/trajopt/src/test_trajopt.cpp | 230 ++++++++++++++++++ 5 files changed, 349 insertions(+) create mode 100644 moveit_planners/trajopt/config/setup.yaml create mode 100644 moveit_planners/trajopt/include/trajopt_planning_context.h create mode 100644 moveit_planners/trajopt/launch/gdb_settings.gdb create mode 100644 moveit_planners/trajopt/launch/test_trajopt_launch.launch create mode 100644 moveit_planners/trajopt/src/test_trajopt.cpp diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h new file mode 100644 index 0000000000..3866c51c10 --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -0,0 +1,84 @@ +#ifndef TrajOpt_PLANNING_CONTEXT_H +#define TrajOpt_PLANNING_CONTEXT_H + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include + +//using namespace trajopt; + +namespace trajopt_interface +{ + +MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); + +struct TrajOptPlannerConfiguration{ + + TrajOptPlannerConfiguration() {} + virtual ~TrajOptPlannerConfiguration() {} + + /** @brief Trajopt problem to be solved (Required) */ + // sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(sco::ModelType::AUTO_SOLVER)); + + std::string model_type; // sco::ModelType::AUTO_SOLVER + sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(model_type)); + + + /** @brief Optimization parameters to be used (Optional) */ + sco::BasicTrustRegionSQPParameters params; + + /** @brief Callback functions called on each iteration of the optimization (Optional) */ + //std::vector callbacks; + sco::Optimizer::Callback callbacks; + +}; + +TrajOptPlannerConfiguration spec_; + +class TrajOptPlanningContext : public planning_interface::PlanningContext +{ +public: + TrajOptPlanningContext(const std::string& name, const std::string& group, + const robot_model::RobotModelConstPtr& model); + ~TrajOptPlanningContext() override + { + } + + bool solve(planning_interface::MotionPlanResponse& res) override; + bool solve(planning_interface::MotionPlanDetailedResponse& res) override; + + bool terminate() override; + void clear() override; + + void setTrajOptPlannerConfiguration(); + + + +protected: + +private: + // trajectory_msgs::JointTrajectory interpolateMultDOF(const std::vector& v1, const std::vector& v2, + // const int& num); + // std::vector interpolateSingleDOF(const double& d1, const double& d2, const int& num); + int dof; + + moveit::core::RobotModelConstPtr robot_model_; + robot_state::RobotStatePtr robot_state_; + + trajectory_msgs::JointTrajectory convert_TrajArray_to_JointTrajectory(const trajopt::TrajArray& traj_array); + + tesseract::tesseract_planning::PlannerRequest tess_request_; +}; +} // namespace trajopt_interface + +#endif // TrajOpt_PLANNING_CONTEXT_H diff --git a/moveit_planners/trajopt/launch/gdb_settings.gdb b/moveit_planners/trajopt/launch/gdb_settings.gdb new file mode 100644 index 0000000000..d8ac14fee4 --- /dev/null +++ b/moveit_planners/trajopt/launch/gdb_settings.gdb @@ -0,0 +1,8 @@ +## This file allows developers to set breakpoints in the CPP_EXECUTABLE_NAME.launch file +## To set a breakpoint, compile with debug flag set to true. Add a line below with the source file name, +## a colon, then the line number to break on. Then launch CPP_EXECUTABLE_NAME with argument debug:=true + +set breakpoint pending on + +## Example break point: +# break CPP_EXECUTABLE_NAME.cpp:52 \ No newline at end of file diff --git a/moveit_planners/trajopt/launch/test_trajopt_launch.launch b/moveit_planners/trajopt/launch/test_trajopt_launch.launch new file mode 100644 index 0000000000..e5931e4b4c --- /dev/null +++ b/moveit_planners/trajopt/launch/test_trajopt_launch.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp new file mode 100644 index 0000000000..af56adc99a --- /dev/null +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -0,0 +1,230 @@ +#include +#include "trajopt_planning_context.h" +#include + +#include +#include +#include +#include +#include +#include +#include +#include "moveit/planning_interface/planning_request.h" + +#include +#include + +// test + +int main(int argc, char** argv) +{ + const std::string node_name = "trajopot_planning_tutorial"; + ros::init(argc, argv, node_name); + ros::AsyncSpinner spinner(1); + spinner.start(); + ros::NodeHandle node_handle("~"); + + const std::string PLANNING_GROUP = "panda_arm"; + robot_model_loader::RobotModelLoaderPtr robot_model_loader(new robot_model_loader::RobotModelLoader("robot_description")); + robot_model::RobotModelPtr robot_model = robot_model_loader->getModel(); + /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ + robot_state::RobotStatePtr robot_state(new robot_state::RobotState(robot_model)); + const robot_state::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); + + const std::vector& joint_names = joint_model_group->getVariableNames(); + + planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); + + // With the planning scene we create a planing scene monitor that + // monitors planning scene diffs and applys them to the planning scene + planning_scene_monitor::PlanningSceneMonitorPtr psm( + new planning_scene_monitor::PlanningSceneMonitor(planning_scene, robot_model_loader)); + psm->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE); + psm->startStateMonitor(); + psm->startSceneMonitor(); + + while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) + { + ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); + } + // We will now construct a loader to load a planner, by name. + // Note that we are using the ROS pluginlib library here. + boost::scoped_ptr> planner_plugin_loader; + planning_interface::PlannerManagerPtr planner_instance; + + std::string planner_plugin_name; + + planner_plugin_name = "trajopt_interface/TrajOptPlanner"; + node_handle.setParam("planning_plugin", planner_plugin_name); + + // We will get the name of planning plugin we want to load + // from the ROS parameter server, and then load the planner + // making sure to catch all exceptions. + if (!node_handle.getParam("planning_plugin", planner_plugin_name)) + ROS_FATAL_STREAM("Could not find planner plugin name"); + try + { + planner_plugin_loader.reset(new pluginlib::ClassLoader( + "moveit_core", "planning_interface::PlannerManager")); + printf("===>>> planner_plugin_name: %s \n", planner_plugin_name.c_str()); + } + catch (pluginlib::PluginlibException& ex) + { + ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); + } + try + { + planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); + if (!planner_instance->initialize(robot_model, node_handle.getNamespace())) // namespace ????. I dont use it + ROS_FATAL_STREAM("Could not initialize planner instance"); + ROS_INFO_STREAM("Using planning interface '" << planner_instance->getDescription() << "'"); + } + catch (pluginlib::PluginlibException& ex) + { + const std::vector& classes = planner_plugin_loader->getDeclaredClasses(); + std::stringstream ss; + for (std::size_t i = 0; i < classes.size(); ++i) + ss << classes[i] << " "; + ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what() << std::endl + << "Available plugins: " << ss.str()); + } + + + + + + + + + + + + + // Visualization + // ^^^^^^^^^^^^^ + // The package MoveItVisualTools provides many capabilties for visualizing objects, robots, + // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script + namespace rvt = rviz_visual_tools; + moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0", rviz_visual_tools::RVIZ_MARKER_TOPIC, psm); + visual_tools.loadRobotStatePub("/display_robot_state"); + visual_tools.enableBatchPublishing(); + visual_tools.deleteAllMarkers(); // clear all old markers + visual_tools.trigger(); + + /* Remote control is an introspection tool that allows users to step through a high level script + via buttons and keyboard shortcuts in RViz */ + visual_tools.loadRemoteControl(); + + /* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/ + Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); + text_pose.translation().z() = 1.75; + visual_tools.publishText(text_pose, "Motion Planning API Demo", rvt::WHITE, rvt::XLARGE); + + /* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */ + visual_tools.trigger(); + + /* We can also use visual_tools to wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); + + // Pose Goal + // ^^^^^^^^^^^^^^^^^^^^^^^^^^^ + // We will now create a motion plan request for the arm of the Panda + // specifying the desired pose of the end-effector as input. + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.trigger(); + planning_interface::MotionPlanRequest req; + planning_interface::MotionPlanResponse res; + geometry_msgs::PoseStamped pose; + pose.header.frame_id = "panda_link0"; + pose.pose.position.x = 0.3; + pose.pose.position.y = 0.4; + pose.pose.position.z = 0.75; + pose.pose.orientation.w = 1.0; + + // A tolerance of 0.01 m is specified in position + // and 0.01 radians in orientation + std::vector tolerance_pose(3, 0.01); + std::vector tolerance_angle(3, 0.01); + + // We will create the request as a constraint using a helper function available + // from the + // `kinematic_constraints`_ + // package. + // + // .. _kinematic_constraints: + // http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132 + moveit_msgs::Constraints pose_goal = + kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); + + req.group_name = PLANNING_GROUP; + req.goal_constraints.push_back(pose_goal); + + // set the request start joint state + // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + + // get the joint values of the start state + std::vector start_joint_values; + robot_state->copyJointGroupPositions(joint_model_group, start_joint_values); + int r = 0; + for (auto x : start_joint_values) + { + printf("===>>> joint: %s with value: %f \n", joint_names[r].c_str(), x); + ++r; + } + req.start_state.joint_state.position = start_joint_values; + + + // set the goal joint state + // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + robot_state::RobotState goal_state(robot_model); + std::vector joint_values = { 0.8, 0.7, 1, 1.3, 1.9, 2.2, 3 }; + goal_state.setJointGroupPositions(joint_model_group, joint_values); + moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); + req.goal_constraints.clear(); + req.goal_constraints.push_back(joint_goal); + + // retrive joint values at goal + std::vector goal_constraints = req.goal_constraints; + std::cout << "===>>> number of constraints in goal: " << goal_constraints.size() << std::endl; + std::vector goal_joint_constraint = goal_constraints[0].joint_constraints; + for (auto x : goal_joint_constraint) + { + std::cout << "==>> joint position at goal " << x.position << std::endl; + } + + + //------ + // We now construct a planning context that encapsulate the scene, + // the request and the response. We call the planner using this + // planning context + planning_interface::PlanningContextPtr context = + planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } + + + + + + + + + + + + + + + + + + + + + +} From 90116aee9a4a293d8f89bd29927a64581f34d43f Mon Sep 17 00:00:00 2001 From: omid1366 Date: Tue, 2 Jul 2019 17:07:38 -0600 Subject: [PATCH 65/96] updated resp req updated planning context working trajopt without any velocity constraint --- moveit_planners/trajopt/config/setup.yaml | 13 ++ .../trajopt/include/problem_description.h | 120 ++++++++++++++++++ .../include/trajopt_planning_context.h | 34 +++-- .../trajopt/launch/test_trajopt_launch.launch | 6 + moveit_planners/trajopt/src/test_trajopt.cpp | 69 +++++----- 5 files changed, 202 insertions(+), 40 deletions(-) create mode 100644 moveit_planners/trajopt/include/problem_description.h diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml index e69de29bb2..f44b12ef66 100644 --- a/moveit_planners/trajopt/config/setup.yaml +++ b/moveit_planners/trajopt/config/setup.yaml @@ -0,0 +1,13 @@ +improve_ratio_threshold: 0.25; +min_trust_box_size: 1e-4; +min_approx_improve: 1e-4; +min_approx_improve_frac: -1000; # should br -infinity +max_iter: 50; +trust_shrink_ratio: 0.1; +trust_expand_ratio: 1.5; +cnt_tolerance: 1e-4; +max_merit_coeff_increases: 5; +merit_coeff_increase_ratio : 10; +max_time: 1000; # should be +infinity +merit_error_coeff: 10; +trust_box_size: 1e-1; diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h new file mode 100644 index 0000000000..73d7d1abe6 --- /dev/null +++ b/moveit_planners/trajopt/include/problem_description.h @@ -0,0 +1,120 @@ +#pragma once +#include +#include +#include +#include +#include + + +namespace trajopt_interface +{ + +class TrajOptProblem; +typedef std::shared_ptr TrajOptProblemPtr; + +/** + * Holds all the data for a trajectory optimization problem + * so you can modify it programmatically, e.g. add your own costs + */ +class TrajOptProblem : public sco::OptProb +{ +public: + TrajOptProblem(); + TrajOptProblem(const int& n_steps, bool& use_time, const robot_model::RobotModelConstPtr& robot_model); + virtual ~TrajOptProblem() = default; + sco::VarVector GetVarRow(int i, int start_col, int num_col) { return m_traj_vars.rblock(i, start_col, num_col); } + sco::VarVector GetVarRow(int i) { return m_traj_vars.row(i); } + sco::Var& GetVar(int i, int j) { return m_traj_vars.at(i, j); } + trajopt::VarArray& GetVars() { return m_traj_vars; } + /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ + int GetNumSteps() { return m_traj_vars.rows(); } + /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. + * Note that this is not necessarily the same as the kinematic DOF.*/ + int GetNumDOF() { return m_traj_vars.cols(); } + // tesseract::BasicKinConstPtr GetKin() { return m_kin; } + //tesseract::BasicEnvConstPtr GetEnv() { return m_env; } + void SetInitTraj(const trajopt::TrajArray& x){ + std::cout << "====>>>>> setInitTraj is called " << std::endl; + std::cout << "x.size: " << x.size() << std::endl; + m_init_traj = x; + // std::cout << m_init_traj << std::endl; + } + trajopt::TrajArray GetInitTraj() { + std::cout << "====>>>>> GetInitTraj is called " << std::endl; + return m_init_traj; + } + // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); + /** @brief Returns TrajOptProb.has_time */ + bool GetHasTime() { return has_time; } + /** @brief Sets TrajOptProb.has_time */ + void SetHasTime(bool tmp) { has_time = tmp; } + +private: + /** @brief If true, the last column in the optimization matrix will be 1/dt */ + bool has_time; + trajopt::VarArray m_traj_vars; + // tesseract::BasicKinConstPtr m_kin; + // tesseract::BasicEnvConstPtr m_env; + trajopt::TrajArray m_init_traj; +}; + +/** +When cost or constraint element of JSON doc is read, one of these guys gets +constructed to hold the parameters. +Then it later gets converted to a Cost object by the hatch method +*/ +struct TermInfo +{ + std::string name; + int term_type; + int getSupportedTypes() { return supported_term_types_; } + // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; + virtual void hatch(TrajOptProblem& prob) = 0; + + // static TermInfoPtr fromName(const std::string& type); + + /** + * Registers a user-defined TermInfo so you can use your own cost + * see function RegisterMakers.cpp + */ + // typedef TermInfoPtr (*MakerFunc)(void); + // static void RegisterMaker(const std::string& type, MakerFunc); + + virtual ~TermInfo() = default; + +protected: + TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) {} +private: + // static std::map name2maker; + int supported_term_types_; +}; + +struct CartPoseTermInfo : public TermInfo +{ + // EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + /** @brief Timestep at which to apply term */ + int timestep; + /** @brief Cartesian position */ + Eigen::Vector3d xyz; + /** @brief Rotation quaternion */ + Eigen::Vector4d wxyz; + /** @brief coefficients for position and rotation */ + Eigen::Vector3d pos_coeffs, rot_coeffs; + /** @brief Link which should reach desired pose */ + std::string link; + /** @brief Static transform applied to the link */ + Eigen::Isometry3d tcp; + + CartPoseTermInfo(); + + /** @brief Used to add term to pci from json */ + // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void hatch(TrajOptProblem& prob) override; + // DEFINE_CREATE(CartPoseTermInfo) +}; + + + +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h index 3866c51c10..01e277eb37 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -15,6 +15,11 @@ #include +#include +#include + +#include "problem_description.h" + //using namespace trajopt; namespace trajopt_interface @@ -24,15 +29,20 @@ MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); struct TrajOptPlannerConfiguration{ - TrajOptPlannerConfiguration() {} + // TrajOptPlannerConfiguration(trajopt::TrajOptProbPtr prob) : prob(prob) {} + + TrajOptPlannerConfiguration() {prob.reset(new TrajOptProblem());} + virtual ~TrajOptPlannerConfiguration() {} - /** @brief Trajopt problem to be solved (Required) */ + // std::string model_type = sco::ModelType::AUTO_SOLVER // sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(sco::ModelType::AUTO_SOLVER)); - std::string model_type; // sco::ModelType::AUTO_SOLVER - sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(model_type)); + /** @brief Trajopt problem to be solved (Required) */ + TrajOptProblemPtr prob; + // TrajOptProblemPtr prob(new TrajOptProblem()); + // std::shared_ptr prob = std::shared_ptr(new TrajOptProblem); /** @brief Optimization parameters to be used (Optional) */ sco::BasicTrustRegionSQPParameters params; @@ -43,8 +53,12 @@ struct TrajOptPlannerConfiguration{ }; +trajopt::TrajArray generateInitialTrajectory(const int& num_steps); TrajOptPlannerConfiguration spec_; +int dof_; +void callBackFunc(sco::OptProb* oprob, sco::OptResults& ores); + class TrajOptPlanningContext : public planning_interface::PlanningContext { public: @@ -62,20 +76,18 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext void setTrajOptPlannerConfiguration(); - - protected: private: - // trajectory_msgs::JointTrajectory interpolateMultDOF(const std::vector& v1, const std::vector& v2, - // const int& num); - // std::vector interpolateSingleDOF(const double& d1, const double& d2, const int& num); - int dof; moveit::core::RobotModelConstPtr robot_model_; robot_state::RobotStatePtr robot_state_; - trajectory_msgs::JointTrajectory convert_TrajArray_to_JointTrajectory(const trajopt::TrajArray& traj_array); + + + trajectory_msgs::JointTrajectory convertTrajArrayToJointTrajectory(const trajopt::TrajArray& traj_array); + + // sco::VarArray convertVarVectorToVarArray(const VarVector& vv); tesseract::tesseract_planning::PlannerRequest tess_request_; }; diff --git a/moveit_planners/trajopt/launch/test_trajopt_launch.launch b/moveit_planners/trajopt/launch/test_trajopt_launch.launch index e5931e4b4c..f0d35bdeaa 100644 --- a/moveit_planners/trajopt/launch/test_trajopt_launch.launch +++ b/moveit_planners/trajopt/launch/test_trajopt_launch.launch @@ -17,6 +17,12 @@ + + + + + + diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp index af56adc99a..55a26c08be 100644 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -31,7 +31,9 @@ int main(int argc, char** argv) robot_state::RobotStatePtr robot_state(new robot_state::RobotState(robot_model)); const robot_state::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); - const std::vector& joint_names = joint_model_group->getVariableNames(); + + const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); + std::cout << ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>> dof: " << joint_names.size() << std::endl; planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); @@ -43,9 +45,9 @@ int main(int argc, char** argv) psm->startStateMonitor(); psm->startSceneMonitor(); - while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) - { - ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); + while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) + { + ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); } // We will now construct a loader to load a planner, by name. // Note that we are using the ROS pluginlib library here. @@ -56,7 +58,7 @@ int main(int argc, char** argv) planner_plugin_name = "trajopt_interface/TrajOptPlanner"; node_handle.setParam("planning_plugin", planner_plugin_name); - + // We will get the name of planning plugin we want to load // from the ROS parameter server, and then load the planner // making sure to catch all exceptions. @@ -192,39 +194,48 @@ int main(int argc, char** argv) std::cout << "==>> joint position at goal " << x.position << std::endl; } - + //------ // We now construct a planning context that encapsulate the scene, // the request and the response. We call the planner using this // planning context - planning_interface::PlanningContextPtr context = + planning_interface::PlanningContextPtr context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); - - context->solve(res); - if (res.error_code_.val != res.error_code_.SUCCESS) + + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) { ROS_ERROR("Could not compute plan successfully"); return 0; } - - - - - - - - - - - - - - - - - - - + visual_tools.prompt("Press 'next' to visualize the reslt "); + +// Visualize the result + // ^^^^^^^^^^^^^^^^^^^^ + ros::Publisher display_publisher = + node_handle.advertise("/move_group/display_planned_path", 1, true); + moveit_msgs::DisplayTrajectory display_trajectory; + + /* Visualize the trajectory */ + moveit_msgs::MotionPlanResponse response; + res.getMessage(response); + + display_trajectory.trajectory_start = response.trajectory_start; + display_trajectory.trajectory.push_back(response.trajectory); + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + /* + // Set the state in the planning scene to the final state of the last plan + robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + planning_scene->setCurrentState(*robot_state.get()); + + // Display the goal state + visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + visual_tools.publishAxisLabeled(pose.pose, "goal_1"); + visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); + visual_tools.trigger(); +*/ } From efd2135a57b71f658929249384924a95ed81aa9f Mon Sep 17 00:00:00 2001 From: Omid Heidari Date: Sun, 14 Jul 2019 21:25:53 -0600 Subject: [PATCH 66/96] added trajopt_interface class --- .../trajopt/include/trajopt_interface.h | 93 +++++++++++++++++++ .../include/trajopt_planning_context.h | 18 ++-- 2 files changed, 104 insertions(+), 7 deletions(-) create mode 100644 moveit_planners/trajopt/include/trajopt_interface.h diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface.h new file mode 100644 index 0000000000..12ce32b414 --- /dev/null +++ b/moveit_planners/trajopt/include/trajopt_interface.h @@ -0,0 +1,93 @@ +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2012, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +/* Author: Omid Heidari */ + +#ifndef TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H +#define TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include + +#include +#include + +#include "problem_description.h" + + +namespace trajopt_interface +{ + // MOVEIT_CLASS_FORWARD(TrajOptInterface); + +class TrajOptInterface //: public trajopt::TrajOptPlanner +{ +public: + TrajOptInterface(); + virtual ~TrajOptInterface() = 0; + + TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); + + const sco::BasicTrustRegionSQPParameters& getParams() const { return params_; } + +protected: + /** @brief Configure everything using the param server */ + void setTrajOptPlannerConfiguration(); + + ros::NodeHandle nh_; /// The ROS node handle + + sco::BasicTrustRegionSQPParameters params_; + + sco::Optimizer::Callback callbacks_; + + TrajOptProblemPtr prob_; + + void callBackFunc(sco::OptProb* oprob, sco::OptResults& ores); + +}; +} + +#endif diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h index 01e277eb37..debb20a29d 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -20,13 +20,15 @@ #include "problem_description.h" +#include "trajopt_interface.h" + //using namespace trajopt; namespace trajopt_interface { MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); - +/* struct TrajOptPlannerConfiguration{ // TrajOptPlannerConfiguration(trajopt::TrajOptProbPtr prob) : prob(prob) {} @@ -38,23 +40,24 @@ struct TrajOptPlannerConfiguration{ // std::string model_type = sco::ModelType::AUTO_SOLVER // sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(sco::ModelType::AUTO_SOLVER)); - /** @brief Trajopt problem to be solved (Required) */ + // @brief Trajopt problem to be solved (Required) TrajOptProblemPtr prob; // TrajOptProblemPtr prob(new TrajOptProblem()); // std::shared_ptr prob = std::shared_ptr(new TrajOptProblem); - /** @brief Optimization parameters to be used (Optional) */ + // @brief Optimization parameters to be used (Optional) sco::BasicTrustRegionSQPParameters params; - /** @brief Callback functions called on each iteration of the optimization (Optional) */ + // @brief Callback functions called on each iteration of the optimization (Optional) //std::vector callbacks; sco::Optimizer::Callback callbacks; }; +*/ -trajopt::TrajArray generateInitialTrajectory(const int& num_steps); -TrajOptPlannerConfiguration spec_; +// trajopt::TrajArray generateInitialTrajectory(const int& num_steps); +//TrajOptPlannerConfiguration spec_; int dof_; void callBackFunc(sco::OptProb* oprob, sco::OptResults& ores); @@ -74,7 +77,7 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext bool terminate() override; void clear() override; - void setTrajOptPlannerConfiguration(); + // void setTrajOptPlannerConfiguration(); protected: @@ -83,6 +86,7 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext moveit::core::RobotModelConstPtr robot_model_; robot_state::RobotStatePtr robot_state_; + TrajOptInterfacePtr trajopot_interface_; trajectory_msgs::JointTrajectory convertTrajArrayToJointTrajectory(const trajopt::TrajArray& traj_array); From 9be1874ed22407be6d1bbdc7746d383724744ecc Mon Sep 17 00:00:00 2001 From: omid1366 Date: Mon, 15 Jul 2019 18:13:53 -0600 Subject: [PATCH 67/96] changed the architectrue and used TrajoptInterface class to contain the solve function details. Created a TrajOptInterface object in TrajoptPlanningContext class instead --- .../trajopt/include/problem_description.h | 2 +- .../trajopt/include/trajopt_interface.h | 25 +++++++--- .../include/trajopt_planning_context.h | 47 +------------------ 3 files changed, 21 insertions(+), 53 deletions(-) diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h index 73d7d1abe6..58286cc273 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/problem_description.h @@ -4,7 +4,7 @@ #include #include #include - +#include namespace trajopt_interface { diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface.h index 12ce32b414..683fa6d187 100644 --- a/moveit_planners/trajopt/include/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface.h @@ -58,24 +58,32 @@ #include "problem_description.h" +#include +#include +#include namespace trajopt_interface { - // MOVEIT_CLASS_FORWARD(TrajOptInterface); +MOVEIT_CLASS_FORWARD(TrajOptInterface); class TrajOptInterface //: public trajopt::TrajOptPlanner { public: - TrajOptInterface(); - virtual ~TrajOptInterface() = 0; - + TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); + virtual ~TrajOptInterface(); const sco::BasicTrustRegionSQPParameters& getParams() const { return params_; } + bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::MotionPlanRequest& req, + const sco::BasicTrustRegionSQPParameters& params, planning_interface::MotionPlanResponse& res) const; // const + + trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); + protected: /** @brief Configure everything using the param server */ - void setTrajOptPlannerConfiguration(); + void setParamsFromRosParamServer(); + void setDefaultParams(); ros::NodeHandle nh_; /// The ROS node handle @@ -85,9 +93,12 @@ class TrajOptInterface //: public trajopt::TrajOptPlanner TrajOptProblemPtr prob_; - void callBackFunc(sco::OptProb* oprob, sco::OptResults& ores); - + // a function to convert TrajArray (TrajArray has no dependency on tesseract) from trajopt_ros to trajectory_msgs::JointTrajectory.Points + trajectory_msgs::JointTrajectory convertTrajArrayToJointTrajectory(const trajopt::TrajArray& traj_array, const std::vector& j_names); }; + +void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); + } #endif diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h index debb20a29d..20edb5cdbb 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -19,7 +19,6 @@ #include #include "problem_description.h" - #include "trajopt_interface.h" //using namespace trajopt; @@ -28,40 +27,7 @@ namespace trajopt_interface { MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); -/* -struct TrajOptPlannerConfiguration{ - - // TrajOptPlannerConfiguration(trajopt::TrajOptProbPtr prob) : prob(prob) {} - - TrajOptPlannerConfiguration() {prob.reset(new TrajOptProblem());} - - virtual ~TrajOptPlannerConfiguration() {} - - // std::string model_type = sco::ModelType::AUTO_SOLVER - // sco::OptProbPtr prob = sco::OptProbPtr(new sco::OptProb(sco::ModelType::AUTO_SOLVER)); - - // @brief Trajopt problem to be solved (Required) - TrajOptProblemPtr prob; - - // TrajOptProblemPtr prob(new TrajOptProblem()); - // std::shared_ptr prob = std::shared_ptr(new TrajOptProblem); - - // @brief Optimization parameters to be used (Optional) - sco::BasicTrustRegionSQPParameters params; - // @brief Callback functions called on each iteration of the optimization (Optional) - //std::vector callbacks; - sco::Optimizer::Callback callbacks; - -}; -*/ - -// trajopt::TrajArray generateInitialTrajectory(const int& num_steps); -//TrajOptPlannerConfiguration spec_; -int dof_; - -void callBackFunc(sco::OptProb* oprob, sco::OptResults& ores); - class TrajOptPlanningContext : public planning_interface::PlanningContext { public: @@ -77,23 +43,14 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext bool terminate() override; void clear() override; - // void setTrajOptPlannerConfiguration(); - protected: private: moveit::core::RobotModelConstPtr robot_model_; - robot_state::RobotStatePtr robot_state_; - - TrajOptInterfacePtr trajopot_interface_; - - - trajectory_msgs::JointTrajectory convertTrajArrayToJointTrajectory(const trajopt::TrajArray& traj_array); - - // sco::VarArray convertVarVectorToVarArray(const VarVector& vv); + // robot_state::RobotStatePtr robot_state_; - tesseract::tesseract_planning::PlannerRequest tess_request_; + TrajOptInterfacePtr trajopt_interface_; }; } // namespace trajopt_interface From ca2857018e4cff3353c14d69df145c935ed1914b Mon Sep 17 00:00:00 2001 From: omid1366 Date: Fri, 19 Jul 2019 17:15:39 -0600 Subject: [PATCH 68/96] added kinematic_terms in problem_description, added comments anout term_type added ProblemInfo, TermInfo, InitInfo, BasicInfo in kinematic_terms, added operator() added ConstructProblem added some param for problem_info --- .../trajopt/include/kinematic_terms.hpp | 41 ++++ .../trajopt/include/problem_description.h | 195 ++++++++++++++---- .../trajopt/include/trajopt_interface.h | 3 +- 3 files changed, 194 insertions(+), 45 deletions(-) create mode 100644 moveit_planners/trajopt/include/kinematic_terms.hpp diff --git a/moveit_planners/trajopt/include/kinematic_terms.hpp b/moveit_planners/trajopt/include/kinematic_terms.hpp new file mode 100644 index 0000000000..4167344ee6 --- /dev/null +++ b/moveit_planners/trajopt/include/kinematic_terms.hpp @@ -0,0 +1,41 @@ +#pragma once +#include +TRAJOPT_IGNORE_WARNINGS_PUSH +#include +TRAJOPT_IGNORE_WARNINGS_POP + +#include +#include +#include +#include + +namespace trajopt_interface +{ + +/** + * @brief Used to calculate the error for StaticCartPoseTermInfo + * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc + */ +struct CartPoseErrCalculator : public VectorOfVector +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + Eigen::Isometry3d target_pose_inv_; + // tesseract::BasicKinConstPtr manip_; + // tesseract::BasicEnvConstPtr env_; + planning_scene::PlanningSceneConstPtr planning_scene_; + std::string link_; + Eigen::Isometry3d tcp_; + + CartPoseErrCalculator(const Eigen::Isometry3d& pose, + const planning_scene::PlanningSceneConstPtr& planning_scene, + std::string link, + Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) + { + } + + Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override; +}; + + +} // namespace trajopt diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h index 58286cc273..a9e8c31868 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/problem_description.h @@ -6,12 +6,153 @@ #include #include +#include + namespace trajopt_interface { +/** +@brief Used to apply cost/constraint to joint-space velocity + +Term is applied to every step between first_step and last_step. It applies two limits, upper_limits/lower_limits, +to the joint velocity subject to the following cases. + +* term_type = TT_COST +** upper_limit = lower_limit = 0 - Cost is applied with a SQUARED error scaled for each joint by coeffs +** upper_limit != lower_limit - 2 hinge costs are applied scaled for each joint by coeffs. If velocity < upper_limit and +velocity > lower_limit, no penalty. + +* term_type = TT_CNT +** upper_limit = lower_limit = 0 - Equality constraint is applied +** upper_limit != lower_limit - 2 Inequality constraints are applied. These are both satisfied when velocity < +upper_limit and velocity > lower_limit + +Note: coeffs, upper_limits, and lower_limits are optional. If a term is not given it will default to 0 for all joints. +If one value is given, this will be broadcast to all joints. + +Note: Velocity is calculated numerically using forward finite difference + +\f{align*}{ + cost = \sum_{t=0}^{T-2} \sum_j c_j (x_{t+1,j} - x_{t,j})^2 +\f} +where j indexes over DOF, and \f$c_j\f$ are the coeffs. +*/ + + +struct TermInfo; +typedef std::shared_ptr TermInfoPtr; + class TrajOptProblem; typedef std::shared_ptr TrajOptProblemPtr; +TrajOptProblemPtr ConstructProblem(const ProblemInfo&); + +struct BasicInfo +{ + /** @brief If true first time step is fixed with a joint level constraint*/ + bool start_fixed; + /** @brief Number of time steps (rows) in the optimization matrix */ + int n_steps; + std::string manip; + std::string robot; // optional + IntVec dofs_fixed; // optional + sco::ModelType convex_solver; // which convex solver to use + + /** @brief If true, the last column in the optimization matrix will be 1/dt */ + bool use_time = false; + /** @brief The upper limit of 1/dt values allowed in the optimization*/ + double dt_upper_lim = 1.0; + /** @brief The lower limit of 1/dt values allowed in the optimization*/ + double dt_lower_lim = 1.0; +}; + +/** +Initialization info read from json +*/ +struct InitInfo +{ + /** @brief Methods of initializing the optimization matrix + + STATIONARY: Initializes all joint values to the initial value (the current value in the env + pci.env->getCurrentJointValues) + JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data + GIVEN_TRAJ: Initializes the matrix to a given trajectory + + In all cases the dt column (if present) is appended the selected method is defined. + */ + enum Type + { + STATIONARY, + JOINT_INTERPOLATED, + GIVEN_TRAJ, + }; + /** @brief Specifies the type of initialization to use */ + Type type; + /** @brief Data used during initialization. Use depends on the initialization selected. */ + TrajArray data; + /** @brief Default value the final column of the optimization is initialized too if time is being used */ + double dt = 1.0; +}; + +/** +When cost or constraint element of JSON doc is read, one of these guys gets +constructed to hold the parameters. +Then it later gets converted to a Cost object by the hatch method +*/ +struct TermInfo +{ + std::string name; + int term_type; + int getSupportedTypes() { return supported_term_types_; } + // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; + virtual void hatch(TrajOptProb& prob) = 0; + + static TermInfoPtr fromName(const std::string& type); + + /** + * Registers a user-defined TermInfo so you can use your own cost + * see function RegisterMakers.cpp + */ + typedef TermInfoPtr (*MakerFunc)(void); + static void RegisterMaker(const std::string& type, MakerFunc); + + virtual ~TermInfo() = default; + +protected: + TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) {} +private: + static std::map name2maker; + int supported_term_types_; +}; + + +struct ProblemInfo +{ +public: + BasicInfo basic_info; + sco::BasicTrustRegionSQPParameters opt_info; + std::vector cost_infos; + std::vector cnt_infos; + InitInfo init_info; + + // tesseract::BasicEnvConstPtr env; + // tesseract::BasicKinConstPtr kin; + planning_scene::PlanningSceneConstPtr planning_scene; + std::string planning_group_name; + + ProblemConstructionInfo(planning_scene::PlanningSceneConstPtr& ps, std::string pg) + : planning_scene_(ps), planning_group_name(pg) {} + // void fromJson(const Json::Value& v); + +private: + // void readBasicInfo(const Json::Value& v); + // void readOptInfo(const Json::Value& v); + // void readCosts(const Json::Value& v); + // void readConstraints(const Json::Value& v); + // void readInitInfo(const Json::Value& v); +}; + + /** * Holds all the data for a trajectory optimization problem * so you can modify it programmatically, e.g. add your own costs @@ -20,7 +161,7 @@ class TrajOptProblem : public sco::OptProb { public: TrajOptProblem(); - TrajOptProblem(const int& n_steps, bool& use_time, const robot_model::RobotModelConstPtr& robot_model); + TrajOptProblem(const int& n_steps, ProblemInfo problem_info); virtual ~TrajOptProblem() = default; sco::VarVector GetVarRow(int i, int start_col, int num_col) { return m_traj_vars.rblock(i, start_col, num_col); } sco::VarVector GetVarRow(int i) { return m_traj_vars.row(i); } @@ -33,16 +174,9 @@ class TrajOptProblem : public sco::OptProb int GetNumDOF() { return m_traj_vars.cols(); } // tesseract::BasicKinConstPtr GetKin() { return m_kin; } //tesseract::BasicEnvConstPtr GetEnv() { return m_env; } - void SetInitTraj(const trajopt::TrajArray& x){ - std::cout << "====>>>>> setInitTraj is called " << std::endl; - std::cout << "x.size: " << x.size() << std::endl; - m_init_traj = x; - // std::cout << m_init_traj << std::endl; - } - trajopt::TrajArray GetInitTraj() { - std::cout << "====>>>>> GetInitTraj is called " << std::endl; - return m_init_traj; - } + planning_scene::PlanningSceneConstPtr GetPlanningScene() { return planning_scene_;} + void SetInitTraj(const trajopt::TrajArray& x){ m_init_traj = x; } + trajopt::TrajArray GetInitTraj() { return m_init_traj; } // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); /** @brief Returns TrajOptProb.has_time */ bool GetHasTime() { return has_time; } @@ -55,40 +189,16 @@ class TrajOptProblem : public sco::OptProb trajopt::VarArray m_traj_vars; // tesseract::BasicKinConstPtr m_kin; // tesseract::BasicEnvConstPtr m_env; + planning_scene::PlanningSceneConstPtr planning_scene_; + std::string planning_group_; trajopt::TrajArray m_init_traj; }; -/** -When cost or constraint element of JSON doc is read, one of these guys gets -constructed to hold the parameters. -Then it later gets converted to a Cost object by the hatch method -*/ -struct TermInfo -{ - std::string name; - int term_type; - int getSupportedTypes() { return supported_term_types_; } - // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void hatch(TrajOptProblem& prob) = 0; - - // static TermInfoPtr fromName(const std::string& type); - - /** - * Registers a user-defined TermInfo so you can use your own cost - * see function RegisterMakers.cpp - */ - // typedef TermInfoPtr (*MakerFunc)(void); - // static void RegisterMaker(const std::string& type, MakerFunc); - - virtual ~TermInfo() = default; -protected: - TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) {} -private: - // static std::map name2maker; - int supported_term_types_; -}; +/** @brief This term is used when the goal frame is fixed in cartesian space + Set term_type == TT_COST or TT_CNT for cost or constraint. +*/ struct CartPoseTermInfo : public TermInfo { // EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -111,10 +221,9 @@ struct CartPoseTermInfo : public TermInfo /** @brief Used to add term to pci from json */ // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; - // DEFINE_CREATE(CartPoseTermInfo) + void hatch(TrajOptProb& prob) override; + DEFINE_CREATE(CartPoseTermInfo) }; - } // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface.h index 683fa6d187..bf1978cf5e 100644 --- a/moveit_planners/trajopt/include/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface.h @@ -71,12 +71,11 @@ class TrajOptInterface //: public trajopt::TrajOptPlanner public: TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); - virtual ~TrajOptInterface(); const sco::BasicTrustRegionSQPParameters& getParams() const { return params_; } bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::MotionPlanRequest& req, - const sco::BasicTrustRegionSQPParameters& params, planning_interface::MotionPlanResponse& res) const; // const + const sco::BasicTrustRegionSQPParameters& params, planning_interface::MotionPlanResponse& res); trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); From d74ef64c67f8ac9158efddbaead01f42ed879415 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Sun, 21 Jul 2019 20:56:01 -0600 Subject: [PATCH 69/96] moved rotVec and concat from kinematics_term header to implementation in problem_Description, added term_type used MotionPlaneRequest from planning_interface instead that of moveit_msgs for solve function input added generateInitiaTrajectory added basic_info to problem_info --- ...{kinematic_terms.hpp => kinematic_terms.h} | 38 +++++++++++++++- .../trajopt/include/problem_description.h | 33 +++++++++++--- .../trajopt/include/trajopt_interface.h | 6 +-- moveit_planners/trajopt/src/test_trajopt.cpp | 44 +++++++++++-------- 4 files changed, 91 insertions(+), 30 deletions(-) rename moveit_planners/trajopt/include/{kinematic_terms.hpp => kinematic_terms.h} (61%) diff --git a/moveit_planners/trajopt/include/kinematic_terms.hpp b/moveit_planners/trajopt/include/kinematic_terms.h similarity index 61% rename from moveit_planners/trajopt/include/kinematic_terms.hpp rename to moveit_planners/trajopt/include/kinematic_terms.h index 4167344ee6..b5223a73b0 100644 --- a/moveit_planners/trajopt/include/kinematic_terms.hpp +++ b/moveit_planners/trajopt/include/kinematic_terms.h @@ -8,15 +8,49 @@ TRAJOPT_IGNORE_WARNINGS_POP #include #include #include +#include + +#include + +#include + +using namespace Eigen; +using namespace std; namespace trajopt_interface { +Vector3d rotVec(const Matrix3d& m) +{ + Quaterniond q; q = m; + return Vector3d(q.x(), q.y(), q.z()); +} + + +VectorXd concat(const VectorXd& a, const VectorXd& b) +{ + VectorXd out(a.size()+b.size()); + out.topRows(a.size()) = a; + out.middleRows(a.size(), b.size()) = b; + return out; +} + +template +vector concat(const vector& a, const vector& b) +{ + vector out; + vector x; + out.insert(out.end(), a.begin(), a.end()); + out.insert(out.end(), b.begin(), b.end()); + return out; +} + + /** * @brief Used to calculate the error for StaticCartPoseTermInfo * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc */ -struct CartPoseErrCalculator : public VectorOfVector +struct CartPoseErrCalculator : public sco::VectorOfVector { EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Isometry3d target_pose_inv_; @@ -27,7 +61,7 @@ struct CartPoseErrCalculator : public VectorOfVector Eigen::Isometry3d tcp_; CartPoseErrCalculator(const Eigen::Isometry3d& pose, - const planning_scene::PlanningSceneConstPtr& planning_scene, + const planning_scene::PlanningSceneConstPtr planning_scene, std::string link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h index a9e8c31868..cab7481232 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/problem_description.h @@ -45,8 +45,26 @@ typedef std::shared_ptr TermInfoPtr; class TrajOptProblem; typedef std::shared_ptr TrajOptProblemPtr; +struct ProblemInfo; + TrajOptProblemPtr ConstructProblem(const ProblemInfo&); + +enum TermType +{ + TT_COST = 0x1, // 0000 0001 + TT_CNT = 0x2, // 0000 0010 + TT_USE_TIME = 0x4, // 0000 0100 +}; + +#define DEFINE_CREATE(classname) \ + static TermInfoPtr create() \ + { \ + TermInfoPtr out(new classname()); \ + return out; \ + } + + struct BasicInfo { /** @brief If true first time step is fixed with a joint level constraint*/ @@ -55,7 +73,7 @@ struct BasicInfo int n_steps; std::string manip; std::string robot; // optional - IntVec dofs_fixed; // optional + sco::IntVec dofs_fixed; // optional sco::ModelType convex_solver; // which convex solver to use /** @brief If true, the last column in the optimization matrix will be 1/dt */ @@ -89,7 +107,7 @@ struct InitInfo /** @brief Specifies the type of initialization to use */ Type type; /** @brief Data used during initialization. Use depends on the initialization selected. */ - TrajArray data; + trajopt::TrajArray data; /** @brief Default value the final column of the optimization is initialized too if time is being used */ double dt = 1.0; }; @@ -105,7 +123,7 @@ struct TermInfo int term_type; int getSupportedTypes() { return supported_term_types_; } // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void hatch(TrajOptProb& prob) = 0; + virtual void hatch(TrajOptProblem& prob) = 0; static TermInfoPtr fromName(const std::string& type); @@ -140,8 +158,8 @@ struct ProblemInfo planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemConstructionInfo(planning_scene::PlanningSceneConstPtr& ps, std::string pg) - : planning_scene_(ps), planning_group_name(pg) {} + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) + : planning_scene(ps), planning_group_name(pg) {} // void fromJson(const Json::Value& v); private: @@ -161,7 +179,7 @@ class TrajOptProblem : public sco::OptProb { public: TrajOptProblem(); - TrajOptProblem(const int& n_steps, ProblemInfo problem_info); + TrajOptProblem(const ProblemInfo& problem_info); virtual ~TrajOptProblem() = default; sco::VarVector GetVarRow(int i, int start_col, int num_col) { return m_traj_vars.rblock(i, start_col, num_col); } sco::VarVector GetVarRow(int i) { return m_traj_vars.row(i); } @@ -221,9 +239,10 @@ struct CartPoseTermInfo : public TermInfo /** @brief Used to add term to pci from json */ // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProb& prob) override; + void hatch(TrajOptProblem& prob) override; DEFINE_CREATE(CartPoseTermInfo) }; +trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); } // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface.h index bf1978cf5e..b4dd24c9b2 100644 --- a/moveit_planners/trajopt/include/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface.h @@ -74,10 +74,10 @@ class TrajOptInterface //: public trajopt::TrajOptPlanner const sco::BasicTrustRegionSQPParameters& getParams() const { return params_; } - bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::MotionPlanRequest& req, - const sco::BasicTrustRegionSQPParameters& params, planning_interface::MotionPlanResponse& res); + bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, const planning_interface::MotionPlanRequest& req, + const sco::BasicTrustRegionSQPParameters& params, moveit_msgs::MotionPlanDetailedResponse& res); + - trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); protected: /** @brief Configure everything using the param server */ diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp index 55a26c08be..232c6f9f54 100644 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -58,7 +58,7 @@ int main(int argc, char** argv) planner_plugin_name = "trajopt_interface/TrajOptPlanner"; node_handle.setParam("planning_plugin", planner_plugin_name); - + // We will get the name of planning plugin we want to load // from the ROS parameter server, and then load the planner // making sure to catch all exceptions. @@ -194,23 +194,20 @@ int main(int argc, char** argv) std::cout << "==>> joint position at goal " << x.position << std::endl; } - - //------ - // We now construct a planning context that encapsulate the scene, - // the request and the response. We call the planner using this + // planning context planning_interface::PlanningContextPtr context = planner_instance->getPlanningContext(planning_scene, req, res.error_code_); - - context->solve(res); - if (res.error_code_.val != res.error_code_.SUCCESS) - { - ROS_ERROR("Could not compute plan successfully"); - return 0; - } - visual_tools.prompt("Press 'next' to visualize the reslt "); - + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } + + visual_tools.prompt("Press 'next' to visualize the reslt "); + // Visualize the result // ^^^^^^^^^^^^^^^^^^^^ ros::Publisher display_publisher = @@ -221,13 +218,24 @@ int main(int argc, char** argv) moveit_msgs::MotionPlanResponse response; res.getMessage(response); + for (int timestep_index = 0; timestep_index < 10; ++timestep_index) + { + for (int joint_index = 0; joint_index < 7; ++joint_index) + { + response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index]; + } + std::cout << "-------------------- next timestep ---------------" << std::endl; + } + + + display_trajectory.trajectory_start = response.trajectory_start; display_trajectory.trajectory.push_back(response.trajectory); visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); visual_tools.trigger(); display_publisher.publish(display_trajectory); - /* - // Set the state in the planning scene to the final state of the last plan + + // Set the state in the planning scene to the final state of the last plan robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); planning_scene->setCurrentState(*robot_state.get()); @@ -235,7 +243,7 @@ int main(int argc, char** argv) visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); visual_tools.publishAxisLabeled(pose.pose, "goal_1"); visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); - visual_tools.trigger(); -*/ + visual_tools.trigger(); + } From 5f016c51769b5d17362b8ccc5ade7e671a665232 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Mon, 22 Jul 2019 20:00:21 -0600 Subject: [PATCH 70/96] added panda_omple_planning added checkParameterSize function in problem_description added JointPoseTermInfo::hatch in problem_description added res.error.code.val to check the request in trajopt_interface.cpp convert req.goal_constraint to JointPoseTermInfo in trajopt_interface.cpp feed the response with the trajopt solution in trajopt_interface.cpp remove comments from trajopt_planning_context.cpp --- .../trajopt/config/panda_ompl_planning.yaml | 203 ++++++++++++++++++ moveit_planners/trajopt/config/setup.yaml | 27 +-- .../trajopt/include/kinematic_terms.h | 5 + .../trajopt/include/problem_description.h | 36 ++++ .../include/trajopt_planning_context.h | 2 - .../trajopt/launch/test_trajopt_launch.launch | 1 + moveit_planners/trajopt/src/test_trajopt.cpp | 114 +++++----- 7 files changed, 310 insertions(+), 78 deletions(-) create mode 100644 moveit_planners/trajopt/config/panda_ompl_planning.yaml diff --git a/moveit_planners/trajopt/config/panda_ompl_planning.yaml b/moveit_planners/trajopt/config/panda_ompl_planning.yaml new file mode 100644 index 0000000000..491e82914e --- /dev/null +++ b/moveit_planners/trajopt/config/panda_ompl_planning.yaml @@ -0,0 +1,203 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ESTkConfigDefault: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECEkConfigDefault: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECEkConfigDefault: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECEkConfigDefault: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRTkConfigDefault: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnectkConfigDefault: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstarkConfigDefault: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRTkConfigDefault: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() + PRMkConfigDefault: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstarkConfigDefault: + type: geometric::PRMstar + FMTkConfigDefault: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMTkConfigDefault: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDSTkConfigDefault: + type: geometric::PDST + STRIDEkConfigDefault: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRTkConfigDefault: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() + frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 + cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf + LBTRRTkConfigDefault: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiESTkConfigDefault: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjESTkConfigDefault: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRMkConfigDefault: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstarkConfigDefault: + type: geometric::LazyPRMstar + SPARSkConfigDefault: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwokConfigDefault: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 + TrajOptDefault: + type: geometric::TrajOpt + +panda_arm: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + - TrajOptDefault +panda_arm_hand: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + - TrajOptDefault +hand: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + - TrajOptDefault diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml index f44b12ef66..d5e7728589 100644 --- a/moveit_planners/trajopt/config/setup.yaml +++ b/moveit_planners/trajopt/config/setup.yaml @@ -1,13 +1,14 @@ -improve_ratio_threshold: 0.25; -min_trust_box_size: 1e-4; -min_approx_improve: 1e-4; -min_approx_improve_frac: -1000; # should br -infinity -max_iter: 50; -trust_shrink_ratio: 0.1; -trust_expand_ratio: 1.5; -cnt_tolerance: 1e-4; -max_merit_coeff_increases: 5; -merit_coeff_increase_ratio : 10; -max_time: 1000; # should be +infinity -merit_error_coeff: 10; -trust_box_size: 1e-1; +trajopt_param: + improve_ratio_threshold: 0.25; + min_trust_box_size: 1e-4; + min_approx_improve: 1e-4; + min_approx_improve_frac: -1000; # should br -infinity + max_iter: 50; + trust_shrink_ratio: 0.1; + trust_expand_ratio: 1.5; + cnt_tolerance: 1e-4; + max_merit_coeff_increases: 5; + merit_coeff_increase_ratio : 10; + max_time: 1000; # should be +infinity + merit_error_coeff: 10; + trust_box_size: 1e-1; diff --git a/moveit_planners/trajopt/include/kinematic_terms.h b/moveit_planners/trajopt/include/kinematic_terms.h index b5223a73b0..25162f8abe 100644 --- a/moveit_planners/trajopt/include/kinematic_terms.h +++ b/moveit_planners/trajopt/include/kinematic_terms.h @@ -71,5 +71,10 @@ struct CartPoseErrCalculator : public sco::VectorOfVector Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override; }; + //TODO(omid): The following should be added and adjusted from trajopt + // JointPosEqCost + // JointPosIneqCost + // JointPosEqConstraint + // JointPosIneqConstraint } // namespace trajopt diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h index cab7481232..77f4adbcc2 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/problem_description.h @@ -243,6 +243,42 @@ struct CartPoseTermInfo : public TermInfo DEFINE_CREATE(CartPoseTermInfo) }; + +/** + \brief Joint space position cost + Position operates on a single point (unlike velocity, etc). This is b/c the primary usecase is joint-space + position waypoints + + \f{align*}{ + \sum_i c_i (x_i - xtarg_i)^2 + \f} + where \f$i\f$ indexes over dof and \f$c_i\f$ are coeffs + */ +struct JointPosTermInfo : public TermInfo +{ + /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec coeffs; + /** @brief Vector of position targets. This is a required value. Size should be the DOF of the system */ + trajopt::DblVec targets; + /** @brief Vector of position upper limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec upper_tols; + /** @brief Vector of position lower limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec lower_tols; + /** @brief First time step to which the term is applied. Default: 0 */ + int first_step = 0; + /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ + int last_step = -1; + + /** @brief Initialize term with it's supported types */ + JointPosTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) {} + + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void hatch(TrajOptProblem& prob) override; + DEFINE_CREATE(JointPosTermInfo) +}; + + + trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); } // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h index 20edb5cdbb..92d6642aa6 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -21,7 +21,6 @@ #include "problem_description.h" #include "trajopt_interface.h" -//using namespace trajopt; namespace trajopt_interface { @@ -48,7 +47,6 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext private: moveit::core::RobotModelConstPtr robot_model_; - // robot_state::RobotStatePtr robot_state_; TrajOptInterfacePtr trajopt_interface_; }; diff --git a/moveit_planners/trajopt/launch/test_trajopt_launch.launch b/moveit_planners/trajopt/launch/test_trajopt_launch.launch index f0d35bdeaa..c80e5c93e1 100644 --- a/moveit_planners/trajopt/launch/test_trajopt_launch.launch +++ b/moveit_planners/trajopt/launch/test_trajopt_launch.launch @@ -28,6 +28,7 @@ + diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp index 232c6f9f54..28c2c27033 100644 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -30,11 +30,9 @@ int main(int argc, char** argv) /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ robot_state::RobotStatePtr robot_state(new robot_state::RobotState(robot_model)); const robot_state::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); - + robot_state->setToDefaultValues(); const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); - std::cout << ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>> dof: " << joint_names.size() << std::endl; - planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); // With the planning scene we create a planing scene monitor that @@ -56,11 +54,13 @@ int main(int argc, char** argv) std::string planner_plugin_name; - planner_plugin_name = "trajopt_interface/TrajOptPlanner"; + planner_plugin_name = "trajopt_interface/TrajOptPlanner"; + + // planner_plugin_name = "ompl_interface/OMPLPlanner"; + // node_handle.getParam("...", ...); + node_handle.setParam("planning_plugin", planner_plugin_name); - // We will get the name of planning plugin we want to load - // from the ROS parameter server, and then load the planner // making sure to catch all exceptions. if (!node_handle.getParam("planning_plugin", planner_plugin_name)) ROS_FATAL_STREAM("Could not find planner plugin name"); @@ -91,19 +91,8 @@ int main(int argc, char** argv) << "Available plugins: " << ss.str()); } - - - - - - - - - - - // Visualization - // ^^^^^^^^^^^^^ + // ======================================================================================== // The package MoveItVisualTools provides many capabilties for visualizing objects, robots, // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script namespace rvt = rviz_visual_tools; @@ -129,7 +118,7 @@ int main(int argc, char** argv) visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); // Pose Goal - // ^^^^^^^^^^^^^^^^^^^^^^^^^^^ + // ======================================================================================== // We will now create a motion plan request for the arm of the Panda // specifying the desired pose of the end-effector as input. visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); @@ -158,12 +147,11 @@ int main(int argc, char** argv) moveit_msgs::Constraints pose_goal = kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); - req.group_name = PLANNING_GROUP; - req.goal_constraints.push_back(pose_goal); + // req.group_name = PLANNING_GROUP; + // req.goal_constraints.push_back(pose_goal); // set the request start joint state - // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - + // ======================================================================================== // get the joint values of the start state std::vector start_joint_values; robot_state->copyJointGroupPositions(joint_model_group, start_joint_values); @@ -173,17 +161,19 @@ int main(int argc, char** argv) printf("===>>> joint: %s with value: %f \n", joint_names[r].c_str(), x); ++r; } - req.start_state.joint_state.position = start_joint_values; + req.start_state.joint_state.name = joint_names; + req.start_state.joint_state.position = start_joint_values; // set the goal joint state - // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + // ======================================================================================== robot_state::RobotState goal_state(robot_model); - std::vector joint_values = { 0.8, 0.7, 1, 1.3, 1.9, 2.2, 3 }; + std::vector joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1}; goal_state.setJointGroupPositions(joint_model_group, joint_values); moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); req.goal_constraints.clear(); req.goal_constraints.push_back(joint_goal); + req.group_name = PLANNING_GROUP; // retrive joint values at goal std::vector goal_constraints = req.goal_constraints; @@ -194,56 +184,54 @@ int main(int argc, char** argv) std::cout << "==>> joint position at goal " << x.position << std::endl; } - // planning context - planning_interface::PlanningContextPtr context = - planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + planning_interface::PlanningContextPtr context = + planner_instance->getPlanningContext(planning_scene, req, res.error_code_); - context->solve(res); - if (res.error_code_.val != res.error_code_.SUCCESS) - { - ROS_ERROR("Could not compute plan successfully"); - return 0; - } + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } - visual_tools.prompt("Press 'next' to visualize the reslt "); + visual_tools.prompt("Press 'next' to visualize the result"); -// Visualize the result - // ^^^^^^^^^^^^^^^^^^^^ - ros::Publisher display_publisher = + // Visualize the result + // ======================================================================================== + ros::Publisher display_publisher = node_handle.advertise("/move_group/display_planned_path", 1, true); - moveit_msgs::DisplayTrajectory display_trajectory; + moveit_msgs::DisplayTrajectory display_trajectory; - /* Visualize the trajectory */ - moveit_msgs::MotionPlanResponse response; - res.getMessage(response); - - for (int timestep_index = 0; timestep_index < 10; ++timestep_index) - { - for (int joint_index = 0; joint_index < 7; ++joint_index) - { - response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index]; - } - std::cout << "-------------------- next timestep ---------------" << std::endl; - } + /* Visualize the trajectory */ + moveit_msgs::MotionPlanResponse response; + res.getMessage(response); + for (int timestep_index = 0; timestep_index < response.trajectory.joint_trajectory.points.size(); ++timestep_index) + { + for (int joint_index = 0; joint_index < response.trajectory.joint_trajectory.points[timestep_index].positions.size(); ++joint_index) + { + std::cout << response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index] << " "; + } + std::cout << std::endl; + } + display_trajectory.trajectory_start = response.trajectory_start; + display_trajectory.trajectory.push_back(response.trajectory); - display_trajectory.trajectory_start = response.trajectory_start; - display_trajectory.trajectory.push_back(response.trajectory); - visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); - visual_tools.trigger(); - display_publisher.publish(display_trajectory); + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); // Set the state in the planning scene to the final state of the last plan - robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); - planning_scene->setCurrentState(*robot_state.get()); + // robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); + // planning_scene->setCurrentState(*robot_state.get()); // Display the goal state - visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); - visual_tools.publishAxisLabeled(pose.pose, "goal_1"); - visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); - visual_tools.trigger(); + // visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); + // visual_tools.publishAxisLabeled(pose.pose, "goal_1"); + // visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); + // visual_tools.trigger(); } From 341230ada83b7440fb0d9adf1e4bb01fd2afe1b7 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Mon, 22 Jul 2019 20:25:57 -0600 Subject: [PATCH 71/96] addressed the comments fixed start state corrected the yaml file multiple joint constraints --- .gitignore | 4 + .../trajopt/config/panda_ompl_planning.yaml | 203 -------- moveit_planners/trajopt/config/setup.yaml | 60 ++- .../trajopt/include/kinematic_terms.h | 62 ++- .../trajopt/include/problem_description.h | 199 ++++--- .../trajopt/include/trajopt_interface.h | 53 +- .../include/trajopt_planning_context.h | 20 +- .../trajopt/launch/gdb_settings.gdb | 8 - .../trajopt/launch/test_trajopt_launch.launch | 1 - moveit_planners/trajopt/src/test_trajopt.cpp | 489 ++++++++++-------- 10 files changed, 526 insertions(+), 573 deletions(-) delete mode 100644 moveit_planners/trajopt/config/panda_ompl_planning.yaml delete mode 100644 moveit_planners/trajopt/launch/gdb_settings.gdb diff --git a/.gitignore b/.gitignore index 808fe85341..cfc7f50ba4 100644 --- a/.gitignore +++ b/.gitignore @@ -58,3 +58,7 @@ qtcreator-* #gdb *.gdb +<<<<<<< HEAD +======= +/moveit_planners/trajopt/launch/gdb_settings.gdb +>>>>>>> addressed the comments diff --git a/moveit_planners/trajopt/config/panda_ompl_planning.yaml b/moveit_planners/trajopt/config/panda_ompl_planning.yaml deleted file mode 100644 index 491e82914e..0000000000 --- a/moveit_planners/trajopt/config/panda_ompl_planning.yaml +++ /dev/null @@ -1,203 +0,0 @@ -planner_configs: - SBLkConfigDefault: - type: geometric::SBL - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ESTkConfigDefault: - type: geometric::EST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LBKPIECEkConfigDefault: - type: geometric::LBKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - BKPIECEkConfigDefault: - type: geometric::BKPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - KPIECEkConfigDefault: - type: geometric::KPIECE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] - failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 - min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 - RRTkConfigDefault: - type: geometric::RRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - RRTConnectkConfigDefault: - type: geometric::RRTConnect - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - RRTstarkConfigDefault: - type: geometric::RRTstar - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 - TRRTkConfigDefault: - type: geometric::TRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 - max_states_failed: 10 # when to start increasing temp. default: 10 - temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 - min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 - init_temperature: 10e-6 # initial temperature. default: 10e-6 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountierNodeRatio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup() - PRMkConfigDefault: - type: geometric::PRM - max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 - PRMstarkConfigDefault: - type: geometric::PRMstar - FMTkConfigDefault: - type: geometric::FMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 - nearest_k: 1 # use Knearest strategy. default: 1 - cache_cc: 1 # use collision checking cache. default: 1 - heuristics: 0 # activate cost to go heuristics. default: 0 - extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - BFMTkConfigDefault: - type: geometric::BFMT - num_samples: 1000 # number of states that the planner should sample. default: 1000 - radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 - nearest_k: 1 # use the Knearest strategy. default: 1 - balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 - optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 - heuristics: 1 # activates cost to go heuristics. default: 1 - cache_cc: 1 # use the collision checking cache. default: 1 - extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 - PDSTkConfigDefault: - type: geometric::PDST - STRIDEkConfigDefault: - type: geometric::STRIDE - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 - degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 - max_degree: 18 # max degree of a node in the GNAT. default: 12 - min_degree: 12 # min degree of a node in the GNAT. default: 12 - max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 - estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 - min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 - BiTRRTkConfigDefault: - type: geometric::BiTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 - init_temperature: 100 # initial temperature. default: 100 - frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup() - frountier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1 - cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf - LBTRRTkConfigDefault: - type: geometric::LBTRRT - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - epsilon: 0.4 # optimality approximation factor. default: 0.4 - BiESTkConfigDefault: - type: geometric::BiEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - ProjESTkConfigDefault: - type: geometric::ProjEST - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 - LazyPRMkConfigDefault: - type: geometric::LazyPRM - range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() - LazyPRMstarkConfigDefault: - type: geometric::LazyPRMstar - SPARSkConfigDefault: - type: geometric::SPARS - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 1000 # maximum consecutive failure limit. default: 1000 - SPARStwokConfigDefault: - type: geometric::SPARStwo - stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 - sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 - dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 - max_failures: 5000 # maximum consecutive failure limit. default: 5000 - TrajOptDefault: - type: geometric::TrajOpt - -panda_arm: - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - - FMTkConfigDefault - - BFMTkConfigDefault - - PDSTkConfigDefault - - STRIDEkConfigDefault - - BiTRRTkConfigDefault - - LBTRRTkConfigDefault - - BiESTkConfigDefault - - ProjESTkConfigDefault - - LazyPRMkConfigDefault - - LazyPRMstarkConfigDefault - - SPARSkConfigDefault - - SPARStwokConfigDefault - - TrajOptDefault -panda_arm_hand: - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - - FMTkConfigDefault - - BFMTkConfigDefault - - PDSTkConfigDefault - - STRIDEkConfigDefault - - BiTRRTkConfigDefault - - LBTRRTkConfigDefault - - BiESTkConfigDefault - - ProjESTkConfigDefault - - LazyPRMkConfigDefault - - LazyPRMstarkConfigDefault - - SPARSkConfigDefault - - SPARStwokConfigDefault - - TrajOptDefault -hand: - planner_configs: - - SBLkConfigDefault - - ESTkConfigDefault - - LBKPIECEkConfigDefault - - BKPIECEkConfigDefault - - KPIECEkConfigDefault - - RRTkConfigDefault - - RRTConnectkConfigDefault - - RRTstarkConfigDefault - - TRRTkConfigDefault - - PRMkConfigDefault - - PRMstarkConfigDefault - - FMTkConfigDefault - - BFMTkConfigDefault - - PDSTkConfigDefault - - STRIDEkConfigDefault - - BiTRRTkConfigDefault - - LBTRRTkConfigDefault - - BiESTkConfigDefault - - ProjESTkConfigDefault - - LazyPRMkConfigDefault - - LazyPRMstarkConfigDefault - - SPARSkConfigDefault - - SPARStwokConfigDefault - - TrajOptDefault diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml index d5e7728589..d844f801d5 100644 --- a/moveit_planners/trajopt/config/setup.yaml +++ b/moveit_planners/trajopt/config/setup.yaml @@ -1,14 +1,48 @@ trajopt_param: - improve_ratio_threshold: 0.25; - min_trust_box_size: 1e-4; - min_approx_improve: 1e-4; - min_approx_improve_frac: -1000; # should br -infinity - max_iter: 50; - trust_shrink_ratio: 0.1; - trust_expand_ratio: 1.5; - cnt_tolerance: 1e-4; - max_merit_coeff_increases: 5; - merit_coeff_increase_ratio : 10; - max_time: 1000; # should be +infinity - merit_error_coeff: 10; - trust_box_size: 1e-1; + improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step + min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence + min_approx_improve: 1e-4 # if model improves less than this, exit and report convergence + min_approx_improve_frac: -.Inf # if model improves less than this, exit and report convergence + max_iter: 100 # The max number of iterations + trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio + trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio + cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done + max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient + merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time + max_time: .inf # not yet implemented + merit_error_coeff: 10 # initial penalty coefficient + trust_box_size: 1e-1 # current size of trust region (component-wise) + +problem_info: + basic_info: + n_steps: 20 # 2 * steps_per_phase + dt_upper_lim: 2.0 # The upper limit of 1/dt values allowed in the optimization + dt_lower_lim: 100.0 # The lower limit of 1/dt values allowed in the optimization + start_fixed: true # if true, start pose is the current pose and the req.start_state is ignored + # if false, the start pose is the one given by req.start_state + use_time: flase # if false, it means the timestep is unit, meaning x1-x0 is the velocity for example + # if true, then cost_infos ro cnt_infos should have TT_USE_TIME for their term_type + convex_solver: 1 # which convex solver to use + # 1 = AUTO_SOLVER, 2 = BPMPD, 3 = OSQP, 4 = QPOASES, 5 = GUROBI + + init_info: + type: 2 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ + # request.start_state should be provided for JOINT_INTERPOLATED and GIVEN_TRAJ + dt: 0.5 + +joint_pos_term_info: + start_pos: + name: start_pos + first_timestep: 0 # First time step to which the term is applied. + last_timestep: 0 # Last time step to which the term is applied. n_steps - 1 + term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME + middle_pos: + name: middle_pos + first_timestep: 10 # First time step to which the term is applied. + last_timestep: 10 # Last time step to which the term is applied. n_steps - 1 + term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME + goal_pos: + name: goal_pos + first_timestep: 19 # First time step to which the term is applied. + last_timestep: 19 # Last time step to which the term is applied. n_steps - 1 + term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME diff --git a/moveit_planners/trajopt/include/kinematic_terms.h b/moveit_planners/trajopt/include/kinematic_terms.h index 25162f8abe..c61052194a 100644 --- a/moveit_planners/trajopt/include/kinematic_terms.h +++ b/moveit_planners/trajopt/include/kinematic_terms.h @@ -1,14 +1,4 @@ #pragma once -#include -TRAJOPT_IGNORE_WARNINGS_PUSH -#include -TRAJOPT_IGNORE_WARNINGS_POP - -#include -#include -#include -#include -#include #include @@ -19,17 +9,16 @@ using namespace std; namespace trajopt_interface { - Vector3d rotVec(const Matrix3d& m) { - Quaterniond q; q = m; + Quaterniond q; + q = m; return Vector3d(q.x(), q.y(), q.z()); } - VectorXd concat(const VectorXd& a, const VectorXd& b) { - VectorXd out(a.size()+b.size()); + VectorXd out(a.size() + b.size()); out.topRows(a.size()) = a; out.middleRows(a.size(), b.size()) = b; return out; @@ -39,13 +28,12 @@ template vector concat(const vector& a, const vector& b) { vector out; - vector x; + vector x(a.size() + b.size()); out.insert(out.end(), a.begin(), a.end()); out.insert(out.end(), b.begin(), b.end()); return out; } - /** * @brief Used to calculate the error for StaticCartPoseTermInfo * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc @@ -54,16 +42,12 @@ struct CartPoseErrCalculator : public sco::VectorOfVector { EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Isometry3d target_pose_inv_; - // tesseract::BasicKinConstPtr manip_; - // tesseract::BasicEnvConstPtr env_; planning_scene::PlanningSceneConstPtr planning_scene_; std::string link_; Eigen::Isometry3d tcp_; - CartPoseErrCalculator(const Eigen::Isometry3d& pose, - const planning_scene::PlanningSceneConstPtr planning_scene, - std::string link, - Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, + std::string link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) { } @@ -71,10 +55,34 @@ struct CartPoseErrCalculator : public sco::VectorOfVector Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override; }; - //TODO(omid): The following should be added and adjusted from trajopt - // JointPosEqCost - // JointPosIneqCost - // JointPosEqConstraint - // JointPosIneqConstraint +// TODO(omid): The following should be added and adjusted from trajopt +// JointPosEqCost +// JointPosIneqCost +// JointPosEqConstraint +// JointPosIneqConstraint + +struct JointVelErrCalculator : sco::VectorOfVector +{ + /** @brief Velocity target */ + double target_; + /** @brief Upper tolerance */ + double upper_tol_; + /** @brief Lower tolerance */ + double lower_tol_; + JointVelErrCalculator() : target_(0.0), upper_tol_(0.0), lower_tol_(0.0) + { + } + JointVelErrCalculator(double target, double upper_tol, double lower_tol) + : target_(target), upper_tol_(upper_tol), lower_tol_(lower_tol) + { + } + + Eigen::VectorXd operator()(const Eigen::VectorXd& var_vals) const; +}; + +struct JointVelJacobianCalculator : sco::MatrixOfVector +{ + Eigen::MatrixXd operator()(const Eigen::VectorXd& var_vals) const; +}; } // namespace trajopt diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/problem_description.h index 77f4adbcc2..8d1bd605e1 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/problem_description.h @@ -1,16 +1,15 @@ #pragma once -#include -#include #include #include #include -#include +#include #include +#include + namespace trajopt_interface { - /** @brief Used to apply cost/constraint to joint-space velocity @@ -38,17 +37,20 @@ Note: Velocity is calculated numerically using forward finite difference where j indexes over DOF, and \f$c_j\f$ are the coeffs. */ - struct TermInfo; -typedef std::shared_ptr TermInfoPtr; +MOVEIT_CLASS_FORWARD(TermInfo); class TrajOptProblem; -typedef std::shared_ptr TrajOptProblemPtr; +MOVEIT_CLASS_FORWARD(TrajOptProblem); -struct ProblemInfo; +struct JointPoseTermInfo; +MOVEIT_CLASS_FORWARD(JointPoseTermInfo); -TrajOptProblemPtr ConstructProblem(const ProblemInfo&); +struct CartPoseTermInfo; +MOVEIT_CLASS_FORWARD(CartPoseTermInfo); +struct ProblemInfo; +TrajOptProblemPtr ConstructProblem(const ProblemInfo&); enum TermType { @@ -57,23 +59,21 @@ enum TermType TT_USE_TIME = 0x4, // 0000 0100 }; -#define DEFINE_CREATE(classname) \ - static TermInfoPtr create() \ - { \ - TermInfoPtr out(new classname()); \ - return out; \ - } - - struct BasicInfo { - /** @brief If true first time step is fixed with a joint level constraint*/ + /** @brief If true, first time step is fixed with a joint level constraint + If this is false, the starting point of the trajectory will + not be the current position of the robot. The use case example is: if we are trying to execute a process like + sanding the critical part which is the actual process path not how we get to the start of the process path. So we + plan the + process path first leaving the start free to hopefully get the most optimal and then we plan from the current + location with + start fixed to the start of the process path. It depends on what we want the default behavior to be + */ bool start_fixed; /** @brief Number of time steps (rows) in the optimization matrix */ int n_steps; - std::string manip; - std::string robot; // optional - sco::IntVec dofs_fixed; // optional + sco::IntVec dofs_fixed; // optional sco::ModelType convex_solver; // which convex solver to use /** @brief If true, the last column in the optimization matrix will be 1/dt */ @@ -89,10 +89,10 @@ Initialization info read from json */ struct InitInfo { - /** @brief Methods of initializing the optimization matrix + /** @brief Methods of initializing the optimization matrix. This defines how robot moves from the current + state to the start state - STATIONARY: Initializes all joint values to the initial value (the current value in the env - pci.env->getCurrentJointValues) + STATIONARY: Initializes all joint values to the initial value (the current value in the env) JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data GIVEN_TRAJ: Initializes the matrix to a given trajectory @@ -106,8 +106,12 @@ struct InitInfo }; /** @brief Specifies the type of initialization to use */ Type type; - /** @brief Data used during initialization. Use depends on the initialization selected. */ - trajopt::TrajArray data; + /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used + to create initialization matrix. We need to give the goal information to this init info + */ + //trajopt::TrajArray data; This data type does not seem correct, it should be of type VectorXd + Eigen::VectorXd end_pos; + trajopt::TrajArray start_to_end_trajectory; /** @brief Default value the final column of the optimization is initialized too if time is being used */ double dt = 1.0; }; @@ -121,7 +125,10 @@ struct TermInfo { std::string name; int term_type; - int getSupportedTypes() { return supported_term_types_; } + int getSupportedTypes() + { + return supported_term_types_; + } // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; virtual void hatch(TrajOptProblem& prob) = 0; @@ -137,13 +144,15 @@ struct TermInfo virtual ~TermInfo() = default; protected: - TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) {} + TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) + { + } + private: static std::map name2maker; int supported_term_types_; }; - struct ProblemInfo { public: @@ -153,66 +162,91 @@ struct ProblemInfo std::vector cnt_infos; InitInfo init_info; - // tesseract::BasicEnvConstPtr env; - // tesseract::BasicKinConstPtr kin; planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) - : planning_scene(ps), planning_group_name(pg) {} - // void fromJson(const Json::Value& v); + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) : planning_scene(ps), planning_group_name(pg) + { + } private: - // void readBasicInfo(const Json::Value& v); - // void readOptInfo(const Json::Value& v); - // void readCosts(const Json::Value& v); - // void readConstraints(const Json::Value& v); - // void readInitInfo(const Json::Value& v); -}; +}; /** * Holds all the data for a trajectory optimization problem * so you can modify it programmatically, e.g. add your own costs */ -class TrajOptProblem : public sco::OptProb +class TrajOptProblem : public sco::OptProb { public: TrajOptProblem(); TrajOptProblem(const ProblemInfo& problem_info); virtual ~TrajOptProblem() = default; - sco::VarVector GetVarRow(int i, int start_col, int num_col) { return m_traj_vars.rblock(i, start_col, num_col); } - sco::VarVector GetVarRow(int i) { return m_traj_vars.row(i); } - sco::Var& GetVar(int i, int j) { return m_traj_vars.at(i, j); } - trajopt::VarArray& GetVars() { return m_traj_vars; } + /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ + sco::VarVector GetVarRow(int i, int start_col, int num_col) + { + return m_traj_vars.rblock(i, start_col, num_col); + } + /** @brief Returns the values of all joints for the specified timestep i.*/ + sco::VarVector GetVarRow(int i) + { + return m_traj_vars.row(i); + } + /** @brief Returns the value of the specified joint j for the specified timestep i.*/ + sco::Var& GetVar(int i, int j) + { + return m_traj_vars.at(i, j); + } + trajopt::VarArray& GetVars() + { + return m_traj_vars; + } /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ - int GetNumSteps() { return m_traj_vars.rows(); } + int GetNumSteps() + { + return m_traj_vars.rows(); + } /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. * Note that this is not necessarily the same as the kinematic DOF.*/ - int GetNumDOF() { return m_traj_vars.cols(); } - // tesseract::BasicKinConstPtr GetKin() { return m_kin; } - //tesseract::BasicEnvConstPtr GetEnv() { return m_env; } - planning_scene::PlanningSceneConstPtr GetPlanningScene() { return planning_scene_;} - void SetInitTraj(const trajopt::TrajArray& x){ m_init_traj = x; } - trajopt::TrajArray GetInitTraj() { return m_init_traj; } + int GetNumDOF() + { + return m_traj_vars.cols(); + } + planning_scene::PlanningSceneConstPtr GetPlanningScene() + { + return planning_scene_; + } + void SetInitTraj(const trajopt::TrajArray& x) + { + m_init_traj = x; + } + trajopt::TrajArray GetInitTraj() + { + return m_init_traj; + } // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); /** @brief Returns TrajOptProb.has_time */ - bool GetHasTime() { return has_time; } + bool GetHasTime() + { + return has_time; + } /** @brief Sets TrajOptProb.has_time */ - void SetHasTime(bool tmp) { has_time = tmp; } + void SetHasTime(bool tmp) + { + has_time = tmp; + } private: /** @brief If true, the last column in the optimization matrix will be 1/dt */ bool has_time; + /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ trajopt::VarArray m_traj_vars; - // tesseract::BasicKinConstPtr m_kin; - // tesseract::BasicEnvConstPtr m_env; planning_scene::PlanningSceneConstPtr planning_scene_; std::string planning_group_; trajopt::TrajArray m_init_traj; }; - /** @brief This term is used when the goal frame is fixed in cartesian space Set term_type == TT_COST or TT_CNT for cost or constraint. @@ -240,9 +274,13 @@ struct CartPoseTermInfo : public TermInfo // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ void hatch(TrajOptProblem& prob) override; - DEFINE_CREATE(CartPoseTermInfo) -}; + static TermInfoPtr create() + { + TermInfoPtr out(new CartPoseTermInfo()); + return out; + } +}; /** \brief Joint space position cost @@ -254,7 +292,7 @@ struct CartPoseTermInfo : public TermInfo \f} where \f$i\f$ indexes over dof and \f$c_i\f$ are coeffs */ -struct JointPosTermInfo : public TermInfo +struct JointPoseTermInfo : public TermInfo { /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ trajopt::DblVec coeffs; @@ -270,15 +308,50 @@ struct JointPosTermInfo : public TermInfo int last_step = -1; /** @brief Initialize term with it's supported types */ - JointPosTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) {} + JointPoseTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) + { + } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ void hatch(TrajOptProblem& prob) override; - DEFINE_CREATE(JointPosTermInfo) + + static TermInfoPtr create() + { + TermInfoPtr out(new JointPoseTermInfo()); + return out; + } }; +struct JointVelTermInfo : public TermInfo +{ + /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec coeffs; + /** @brief Vector of velocity targets. This is a required value. Size should be the DOF of the system */ + trajopt::DblVec targets; + /** @brief Vector of velocity upper limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec upper_tols; + /** @brief Vector of velocity lower limits. Size should be the DOF of the system. Default: vector of 0's*/ + trajopt::DblVec lower_tols; + /** @brief First time step to which the term is applied. Default: 0*/ + int first_step = 0; + /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ + int last_step = -1; + + /** @brief Initialize term with it's supported types */ + JointVelTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) + { + } + /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ + void hatch(TrajOptProblem& prob) override; + + static TermInfoPtr create() + { + TermInfoPtr out(new JointVelTermInfo()); + return out; + } +}; -trajopt::TrajArray generateInitialTrajectory(const int& num_steps, const std::vector& joint_vals); + void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, trajopt::TrajArray& init_traj); } // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface.h index b4dd24c9b2..deabc02168 100644 --- a/moveit_planners/trajopt/include/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface.h @@ -1,7 +1,7 @@ /********************************************************************* * Software License Agreement (BSD License) * - * Copyright (c) 2012, Willow Garage, Inc. + * Copyright (c) 2019, PickNik, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. - * * Neither the name of Willow Garage nor the names of its + * * Neither the name of PickNik nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * @@ -39,65 +39,44 @@ #include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include - -#include - -#include #include #include "problem_description.h" -#include -#include #include namespace trajopt_interface { MOVEIT_CLASS_FORWARD(TrajOptInterface); -class TrajOptInterface //: public trajopt::TrajOptPlanner +class TrajOptInterface { public: + TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); - TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); - - const sco::BasicTrustRegionSQPParameters& getParams() const { return params_; } - - bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, const planning_interface::MotionPlanRequest& req, - const sco::BasicTrustRegionSQPParameters& params, moveit_msgs::MotionPlanDetailedResponse& res); - + const sco::BasicTrustRegionSQPParameters& getParams() const + { + return params_; + } + bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, + const planning_interface::MotionPlanRequest& req, + moveit_msgs::MotionPlanDetailedResponse& res); protected: /** @brief Configure everything using the param server */ - void setParamsFromRosParamServer(); - void setDefaultParams(); + void setTrajOptParams(sco::BasicTrustRegionSQPParameters& param); + void setDefaultTrajOPtParams(); + void setProblemInfoParam(ProblemInfo& problem_info); + void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); ros::NodeHandle nh_; /// The ROS node handle - sco::BasicTrustRegionSQPParameters params_; - - sco::Optimizer::Callback callbacks_; - + std::vector callbacks_; TrajOptProblemPtr prob_; - - // a function to convert TrajArray (TrajArray has no dependency on tesseract) from trajopt_ros to trajectory_msgs::JointTrajectory.Points - trajectory_msgs::JointTrajectory convertTrajArrayToJointTrajectory(const trajopt::TrajArray& traj_array, const std::vector& j_names); }; void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); - } #endif diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_planning_context.h index 92d6642aa6..3a6497bcf8 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_planning_context.h @@ -1,30 +1,14 @@ #ifndef TrajOpt_PLANNING_CONTEXT_H #define TrajOpt_PLANNING_CONTEXT_H -#include -#include #include -#include -#include -#include -#include -#include - -#include - -#include - -#include -#include #include "problem_description.h" #include "trajopt_interface.h" - namespace trajopt_interface { - MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); class TrajOptPlanningContext : public planning_interface::PlanningContext @@ -43,13 +27,11 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext void clear() override; protected: - private: - moveit::core::RobotModelConstPtr robot_model_; TrajOptInterfacePtr trajopt_interface_; }; -} // namespace trajopt_interface +} // namespace trajopt_interface #endif // TrajOpt_PLANNING_CONTEXT_H diff --git a/moveit_planners/trajopt/launch/gdb_settings.gdb b/moveit_planners/trajopt/launch/gdb_settings.gdb deleted file mode 100644 index d8ac14fee4..0000000000 --- a/moveit_planners/trajopt/launch/gdb_settings.gdb +++ /dev/null @@ -1,8 +0,0 @@ -## This file allows developers to set breakpoints in the CPP_EXECUTABLE_NAME.launch file -## To set a breakpoint, compile with debug flag set to true. Add a line below with the source file name, -## a colon, then the line number to break on. Then launch CPP_EXECUTABLE_NAME with argument debug:=true - -set breakpoint pending on - -## Example break point: -# break CPP_EXECUTABLE_NAME.cpp:52 \ No newline at end of file diff --git a/moveit_planners/trajopt/launch/test_trajopt_launch.launch b/moveit_planners/trajopt/launch/test_trajopt_launch.launch index c80e5c93e1..f0d35bdeaa 100644 --- a/moveit_planners/trajopt/launch/test_trajopt_launch.launch +++ b/moveit_planners/trajopt/launch/test_trajopt_launch.launch @@ -28,7 +28,6 @@ - diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp index 28c2c27033..5b3d48a1c2 100644 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -2,8 +2,13 @@ #include "trajopt_planning_context.h" #include +#include +#include + #include #include +#include + #include #include #include @@ -14,224 +19,304 @@ #include #include -// test +#include +#include +#include +#include + + +// This file is a test for using trajopt in MoveIt. The goal is to make different types of constraints in +// MotionPlanRequest +// and visualize the result using trajopt planner. +// Three cases: +// 1- joint constraint with start_fixed true, meaining current state of the robot is the initial state of trajectory. +// 2- joint constraint with start_fixed false, meainig more than one goal should be given. The robot jumps to the first +// goal +// and motion planning is done between first goal and second goal. +// 3- Cartesian constraint. int main(int argc, char** argv) { - const std::string node_name = "trajopot_planning_tutorial"; - ros::init(argc, argv, node_name); - ros::AsyncSpinner spinner(1); - spinner.start(); - ros::NodeHandle node_handle("~"); - - const std::string PLANNING_GROUP = "panda_arm"; - robot_model_loader::RobotModelLoaderPtr robot_model_loader(new robot_model_loader::RobotModelLoader("robot_description")); - robot_model::RobotModelPtr robot_model = robot_model_loader->getModel(); - /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ - robot_state::RobotStatePtr robot_state(new robot_state::RobotState(robot_model)); - const robot_state::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); - robot_state->setToDefaultValues(); - - const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); - planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); - - // With the planning scene we create a planing scene monitor that - // monitors planning scene diffs and applys them to the planning scene - planning_scene_monitor::PlanningSceneMonitorPtr psm( - new planning_scene_monitor::PlanningSceneMonitor(planning_scene, robot_model_loader)); - psm->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE); - psm->startStateMonitor(); - psm->startSceneMonitor(); - - while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) - { - ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); - } - // We will now construct a loader to load a planner, by name. - // Note that we are using the ROS pluginlib library here. - boost::scoped_ptr> planner_plugin_loader; - planning_interface::PlannerManagerPtr planner_instance; - - std::string planner_plugin_name; - - planner_plugin_name = "trajopt_interface/TrajOptPlanner"; - - // planner_plugin_name = "ompl_interface/OMPLPlanner"; - // node_handle.getParam("...", ...); - - node_handle.setParam("planning_plugin", planner_plugin_name); - - // making sure to catch all exceptions. - if (!node_handle.getParam("planning_plugin", planner_plugin_name)) - ROS_FATAL_STREAM("Could not find planner plugin name"); - try - { - planner_plugin_loader.reset(new pluginlib::ClassLoader( - "moveit_core", "planning_interface::PlannerManager")); - printf("===>>> planner_plugin_name: %s \n", planner_plugin_name.c_str()); - } - catch (pluginlib::PluginlibException& ex) - { - ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); - } - try - { - planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); - if (!planner_instance->initialize(robot_model, node_handle.getNamespace())) // namespace ????. I dont use it - ROS_FATAL_STREAM("Could not initialize planner instance"); - ROS_INFO_STREAM("Using planning interface '" << planner_instance->getDescription() << "'"); - } - catch (pluginlib::PluginlibException& ex) - { - const std::vector& classes = planner_plugin_loader->getDeclaredClasses(); - std::stringstream ss; - for (std::size_t i = 0; i < classes.size(); ++i) - ss << classes[i] << " "; - ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what() << std::endl - << "Available plugins: " << ss.str()); - } - - // Visualization - // ======================================================================================== - // The package MoveItVisualTools provides many capabilties for visualizing objects, robots, - // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script - namespace rvt = rviz_visual_tools; - moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0", rviz_visual_tools::RVIZ_MARKER_TOPIC, psm); - visual_tools.loadRobotStatePub("/display_robot_state"); - visual_tools.enableBatchPublishing(); - visual_tools.deleteAllMarkers(); // clear all old markers - visual_tools.trigger(); - - /* Remote control is an introspection tool that allows users to step through a high level script - via buttons and keyboard shortcuts in RViz */ - visual_tools.loadRemoteControl(); - - /* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/ - Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); - text_pose.translation().z() = 1.75; - visual_tools.publishText(text_pose, "Motion Planning API Demo", rvt::WHITE, rvt::XLARGE); - - /* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */ - visual_tools.trigger(); - - /* We can also use visual_tools to wait for user input */ - visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); - - // Pose Goal - // ======================================================================================== - // We will now create a motion plan request for the arm of the Panda - // specifying the desired pose of the end-effector as input. - visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); - visual_tools.trigger(); - planning_interface::MotionPlanRequest req; - planning_interface::MotionPlanResponse res; - geometry_msgs::PoseStamped pose; - pose.header.frame_id = "panda_link0"; - pose.pose.position.x = 0.3; - pose.pose.position.y = 0.4; - pose.pose.position.z = 0.75; - pose.pose.orientation.w = 1.0; - - // A tolerance of 0.01 m is specified in position - // and 0.01 radians in orientation - std::vector tolerance_pose(3, 0.01); - std::vector tolerance_angle(3, 0.01); - - // We will create the request as a constraint using a helper function available - // from the - // `kinematic_constraints`_ - // package. - // - // .. _kinematic_constraints: - // http://docs.ros.org/indigo/api/moveit_core/html/namespacekinematic__constraints.html#a88becba14be9ced36fefc7980271e132 - moveit_msgs::Constraints pose_goal = - kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); - - // req.group_name = PLANNING_GROUP; - // req.goal_constraints.push_back(pose_goal); - - // set the request start joint state - // ======================================================================================== - // get the joint values of the start state - std::vector start_joint_values; - robot_state->copyJointGroupPositions(joint_model_group, start_joint_values); - int r = 0; - for (auto x : start_joint_values) - { - printf("===>>> joint: %s with value: %f \n", joint_names[r].c_str(), x); - ++r; - } + const std::string node_name = "trajopot_planning_tutorial"; + ros::init(argc, argv, node_name); + ros::AsyncSpinner spinner(1); + spinner.start(); + ros::NodeHandle node_handle("~"); + + const std::string PLANNING_GROUP = "panda_arm"; + robot_model_loader::RobotModelLoaderPtr robot_model_loader( + new robot_model_loader::RobotModelLoader("robot_description")); + robot_model::RobotModelPtr robot_model = robot_model_loader->getModel(); + + /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ + robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model)); + current_state->setToDefaultValues(); + + const robot_state::JointModelGroup* joint_model_group = current_state->getJointModelGroup(PLANNING_GROUP); + const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); + planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); + + // With the planning scene we create a planing scene monitor that + // monitors planning scene diffs and applys them to the planning scene + planning_scene_monitor::PlanningSceneMonitorPtr psm( + new planning_scene_monitor::PlanningSceneMonitor(planning_scene, robot_model_loader)); + psm->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE); + psm->startStateMonitor(); + psm->startSceneMonitor(); + + // set the start joint state + // ======================================================================================== + // panda_arm joint limits: + // -2.8973 2.8973 + // -1.7628 1.7628 + // -2.8973 2.8973 + // -3.0718 -0.0698 + // -2.8973 2.8973 + // -0.0175 3.7525 + // -2.8973 2.8973 + + std::vector start_joint_values = {0.4, 0.3, 0.5, -0.55, 0.88, 1.0, -0.075 }; + robot_state::RobotStatePtr start_state(new robot_state::RobotState(robot_model)); + start_state->setJointGroupPositions(joint_model_group, start_joint_values); + start_state->update(); + + // planning_scene->setCurrentState(*robot_state); + + // get the joint values of the start state + // std::vector tmp_joint_values; + // robot_state->copyJointGroupPositions(joint_model_group, tmp_joint_values); + // int r = 0; + // for (auto x : tmp_joint_values) + // { + // printf("===>>> joint: %s with start value: %f \n", joint_names[r].c_str(), x); + // ++r; + // } + + // printf("--- get the joint values from planning scene current state"); + // robot_state::RobotState current_state = planning_scene->getCurrentState(); + // std::vector tmp_j_values; + // current_state.copyJointGroupPositions(joint_model_group, tmp_j_values); + // r = 0; + // for (auto x : tmp_j_values) + // { + // printf("===>>> joint: %s with start value: %f \n", joint_names[r].c_str(), x); + // ++r; + // } + + + + // ======================================================================================== + + while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) + { + ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); + } + // We will now construct a loader to load a planner, by name. + // Note that we are using the ROS pluginlib library here. + boost::scoped_ptr> planner_plugin_loader; + planning_interface::PlannerManagerPtr planner_instance; + + std::string planner_plugin_name; + + planner_plugin_name = "trajopt_interface/TrajOptPlanner"; + node_handle.setParam("planning_plugin", planner_plugin_name); + + // making sure to catch all exceptions. + if (!node_handle.getParam("planning_plugin", planner_plugin_name)) + ROS_FATAL_STREAM("Could not find planner plugin name"); + try + { + planner_plugin_loader.reset(new pluginlib::ClassLoader( + "moveit_core", "planning_interface::PlannerManager")); + printf("===>>> planner_plugin_name: %s \n", planner_plugin_name.c_str()); + } + catch (pluginlib::PluginlibException& ex) + { + ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); + } + try + { + planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); + if (!planner_instance->initialize(robot_model, node_handle.getNamespace())) // namespace ????. I dont use it + ROS_FATAL_STREAM("Could not initialize planner instance"); + ROS_INFO_STREAM("Using planning interface '" << planner_instance->getDescription() << "'"); + } + catch (pluginlib::PluginlibException& ex) + { + const std::vector& classes = planner_plugin_loader->getDeclaredClasses(); + std::stringstream ss; + for (std::size_t i = 0; i < classes.size(); ++i) + ss << classes[i] << " "; + ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what() << std::endl + << "Available plugins: " << ss.str()); + } + + // Visualization + // ======================================================================================== + // The package MoveItVisualTools provides many capabilties for visualizing objects, robots, + // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script + namespace rvt = rviz_visual_tools; + moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0", rviz_visual_tools::RVIZ_MARKER_TOPIC, psm); + visual_tools.loadRobotStatePub("/display_robot_state"); + visual_tools.enableBatchPublishing(); + visual_tools.deleteAllMarkers(); // clear all old markers + visual_tools.trigger(); + + /* Remote control is an introspection tool that allows users to step through a high level script + via buttons and keyboard shortcuts in RViz */ + visual_tools.loadRemoteControl(); + + /* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/ + Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); + text_pose.translation().z() = 1.75; + visual_tools.publishText(text_pose, "Motion Planning API Demo", rvt::WHITE, rvt::XLARGE); + + /* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */ + visual_tools.trigger(); + + /* We can also use visual_tools to wait for user input */ + visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); + + // res req + planning_interface::MotionPlanRequest req; + planning_interface::MotionPlanResponse res; + + req.start_state.joint_state.name = joint_names; + req.start_state.joint_state.position = start_joint_values; + + // set the goal joint state and joints tolerance + // ======================================================================================== + robot_state::RobotState goal_state(robot_model); + std::vector goal_joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1 }; + goal_state.setJointGroupPositions(joint_model_group, goal_joint_values); + moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); + req.goal_constraints.clear(); + req.goal_constraints.push_back(joint_goal); + req.group_name = PLANNING_GROUP; + req.goal_constraints[0].name = "goal_pos"; + + // set joint tolerance + std::vector goal_joint_constraint = req.goal_constraints[0].joint_constraints; + for (int x = 0; x < goal_joint_constraint.size(); ++x) + { + std::cout << "==>> joint position at goal " << goal_joint_constraint[x].position << std::endl; + req.goal_constraints[0].joint_constraints[x].tolerance_above = 0.1; + req.goal_constraints[0].joint_constraints[x].tolerance_below = 0.1; + } + + robot_state::RobotState middle_state(robot_model); + std::vector middle_joint_values = {0.5, 0.4, 0.65, -0.75, 1.05, 1.25, -0.15 }; + middle_state.setJointGroupPositions(joint_model_group, middle_joint_values); + middle_state.update(); + moveit_msgs::Constraints joint_middle = kinematic_constraints::constructGoalConstraints(middle_state, joint_model_group); + req.goal_constraints.push_back(joint_middle); + req.goal_constraints[1].name = "middle_pos"; + std::cout << "hereeeeeeeeeeeeeeeeeeeeeeee 1 " << req.goal_constraints[1].joint_constraints[0].position << std::endl; + std::vector middle_joint_constraint = req.goal_constraints[1].joint_constraints; + std::cout << "hereeeeeeeeeeeeeeeeeeeeeeee 2" << std::endl; + for (int x = 0; x < middle_joint_constraint.size(); ++x) + { + std::cout << "==>> joint position at middle " << middle_joint_constraint[x].position << std::endl; + req.goal_constraints[1].joint_constraints[x].tolerance_above = 0.1; + req.goal_constraints[1].joint_constraints[x].tolerance_below = 0.1; + } + + std::cout << "===>>> number of constraints in goal: " << req.goal_constraints.size() << std::endl; + // planning context + // ======================================================================================== + planning_interface::PlanningContextPtr context = + planner_instance->getPlanningContext(planning_scene, req, res.error_code_); - req.start_state.joint_state.name = joint_names; - req.start_state.joint_state.position = start_joint_values; - - // set the goal joint state - // ======================================================================================== - robot_state::RobotState goal_state(robot_model); - std::vector joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1}; - goal_state.setJointGroupPositions(joint_model_group, joint_values); - moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); - req.goal_constraints.clear(); - req.goal_constraints.push_back(joint_goal); - req.group_name = PLANNING_GROUP; - - // retrive joint values at goal - std::vector goal_constraints = req.goal_constraints; - std::cout << "===>>> number of constraints in goal: " << goal_constraints.size() << std::endl; - std::vector goal_joint_constraint = goal_constraints[0].joint_constraints; - for (auto x : goal_joint_constraint) - { - std::cout << "==>> joint position at goal " << x.position << std::endl; - } + context->solve(res); + if (res.error_code_.val != res.error_code_.SUCCESS) + { + ROS_ERROR("Could not compute plan successfully"); + return 0; + } - // planning context - planning_interface::PlanningContextPtr context = - planner_instance->getPlanningContext(planning_scene, req, res.error_code_); + visual_tools.prompt("Press 'next' to visualize the result"); + + // Visualize the result + // ======================================================================================== + ros::Publisher display_publisher = + node_handle.advertise("/move_group/display_planned_path", 1, true); + moveit_msgs::DisplayTrajectory display_trajectory; + + /* Visualize the trajectory */ + moveit_msgs::MotionPlanResponse response; + res.getMessage(response); - context->solve(res); - if (res.error_code_.val != res.error_code_.SUCCESS) + for (int timestep_index = 0; timestep_index < response.trajectory.joint_trajectory.points.size(); ++timestep_index) + { + for (int joint_index = 0; + joint_index < response.trajectory.joint_trajectory.points[timestep_index].positions.size(); ++joint_index) { - ROS_ERROR("Could not compute plan successfully"); - return 0; + std::cout << response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index] << " "; } + std::cout << std::endl; + } - visual_tools.prompt("Press 'next' to visualize the result"); + display_trajectory.trajectory_start = response.trajectory_start; + display_trajectory.trajectory.push_back(response.trajectory); - // Visualize the result - // ======================================================================================== - ros::Publisher display_publisher = - node_handle.advertise("/move_group/display_planned_path", 1, true); - moveit_msgs::DisplayTrajectory display_trajectory; + visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); + visual_tools.trigger(); + display_publisher.publish(display_trajectory); + + + std::cout << "===>>> group name:" << response.group_name << std::endl; + std::cout << "===>>> traj start joint name size: " << response.trajectory_start.joint_state.name.size() << std::endl; + std::cout << "===>>> traj start joint position size: " << response.trajectory_start.joint_state.position.size() + << std::endl; + + std::cout << "===>>> traj joint names size: " << response.trajectory.joint_trajectory.joint_names.size() << std::endl; + + for (int jn = 0; jn < response.trajectory.joint_trajectory.joint_names.size(); ++jn) + { + std::cout << "===>>> joint_" << jn << ": " << response.trajectory.joint_trajectory.joint_names[jn] << std::endl; + } + + + const std::vector& str = joint_model_group->getLinkModelNames(); + printf("end effector name %s\n", str.back().c_str()); + + const Eigen::Affine3d& end_effector_transform_current = current_state->getGlobalLinkTransform(str.back()); + geometry_msgs::PoseStamped pose_msg; + pose_msg.header.stamp = ros::Time::now(); + pose_msg.header.frame_id = robot_model->getModelFrame(); + pose_msg.pose = tf2::toMsg(end_effector_transform_current); + + visual_tools.publishAxisLabeled(pose_msg.pose, "current"); + visual_tools.publishText(text_pose, "current pose", rvt::WHITE, rvt::XLARGE); + visual_tools.trigger(); - /* Visualize the trajectory */ - moveit_msgs::MotionPlanResponse response; - res.getMessage(response); + const Eigen::Affine3d& end_effector_transform_start = start_state->getGlobalLinkTransform(str.back()); + pose_msg.header.stamp = ros::Time::now(); + pose_msg.header.frame_id = robot_model->getModelFrame(); + pose_msg.pose = tf2::toMsg(end_effector_transform_start); - for (int timestep_index = 0; timestep_index < response.trajectory.joint_trajectory.points.size(); ++timestep_index) - { - for (int joint_index = 0; joint_index < response.trajectory.joint_trajectory.points[timestep_index].positions.size(); ++joint_index) - { - std::cout << response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index] << " "; - } - std::cout << std::endl; - } + visual_tools.publishAxisLabeled(pose_msg.pose, "start"); + visual_tools.publishText(text_pose, "start pose", rvt::BLUE, rvt::XLARGE); + visual_tools.trigger(); - display_trajectory.trajectory_start = response.trajectory_start; - display_trajectory.trajectory.push_back(response.trajectory); - visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); - visual_tools.trigger(); - display_publisher.publish(display_trajectory); + const Eigen::Affine3d& end_effector_transform_middle = middle_state.getGlobalLinkTransform(str.back()); + pose_msg.header.stamp = ros::Time::now(); + pose_msg.header.frame_id = robot_model->getModelFrame(); + pose_msg.pose = tf2::toMsg(end_effector_transform_middle); - // Set the state in the planning scene to the final state of the last plan - // robot_state->setJointGroupPositions(joint_model_group, response.trajectory.joint_trajectory.points.back().positions); - // planning_scene->setCurrentState(*robot_state.get()); + visual_tools.publishAxisLabeled(pose_msg.pose, "middle"); + visual_tools.publishText(text_pose, "middle pose", rvt::BLUE, rvt::XLARGE); + visual_tools.trigger(); - // Display the goal state - // visual_tools.publishRobotState(planning_scene->getCurrentStateNonConst(), rviz_visual_tools::GREEN); - // visual_tools.publishAxisLabeled(pose.pose, "goal_1"); - // visual_tools.publishText(text_pose, "Pose Goal (1)", rvt::WHITE, rvt::XLARGE); - // visual_tools.trigger(); + const Eigen::Affine3d& end_effector_transform_goal = goal_state.getGlobalLinkTransform(str.back()); + pose_msg.header.stamp = ros::Time::now(); + pose_msg.header.frame_id = robot_model->getModelFrame(); + pose_msg.pose = tf2::toMsg(end_effector_transform_goal); + visual_tools.publishAxisLabeled(pose_msg.pose, "goal"); + visual_tools.publishText(text_pose, "goal pose", rvt::BLUE, rvt::XLARGE); + visual_tools.trigger(); + visual_tools.prompt("Press 'next' to finish demo \n"); } From f722b0ff2ea9eed7c48622588354c184ff6ecc8b Mon Sep 17 00:00:00 2001 From: omid1366 Date: Tue, 30 Jul 2019 14:55:02 -0600 Subject: [PATCH 72/96] addressed some comments leave setup assistant changes for later on another PR cleaned up test_trajopt added unittest --- moveit_planners/trajopt/config/setup.yaml | 42 ++--- .../trajopt_interface/kinematic_terms.h | 39 ++-- .../kinematic_terms.h~HEAD} | 41 +++-- .../trajopt_interface/problem_description.h | 49 +++-- .../problem_description.h~HEAD} | 60 ++++--- .../trajopt_interface/trajopt_interface.h | 20 ++- .../trajopt_interface.h~HEAD} | 25 ++- .../trajopt_planning_context.h | 10 +- .../trajopt_planning_context.h~HEAD} | 11 +- moveit_planners/trajopt/src/test_trajopt.cpp | 170 ++++++------------ .../widgets/configuration_files_widget.cpp | 21 --- 11 files changed, 209 insertions(+), 279 deletions(-) rename moveit_planners/trajopt/include/{kinematic_terms.h => trajopt_interface/kinematic_terms.h~HEAD} (63%) rename moveit_planners/trajopt/include/{problem_description.h => trajopt_interface/problem_description.h~HEAD} (88%) rename moveit_planners/trajopt/include/{trajopt_interface.h => trajopt_interface/trajopt_interface.h~HEAD} (83%) rename moveit_planners/trajopt/include/{trajopt_planning_context.h => trajopt_interface/trajopt_planning_context.h~HEAD} (80%) diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml index d844f801d5..d3c8518cdd 100644 --- a/moveit_planners/trajopt/config/setup.yaml +++ b/moveit_planners/trajopt/config/setup.yaml @@ -1,24 +1,24 @@ trajopt_param: - improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step - min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence + improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step. [Research Paper] TrueImprove/ModelImprove > c + min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence. [Research Paper] xtol min_approx_improve: 1e-4 # if model improves less than this, exit and report convergence min_approx_improve_frac: -.Inf # if model improves less than this, exit and report convergence max_iter: 100 # The max number of iterations - trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio - trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio - cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done - max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient - merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time + trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao- + trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao+ + cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done. [Research Paper] ctol + max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient. [Reasearch Paper] Max iteration in PenaltyIteration loop + merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time. [Researcy Paper] Penalty scaling factory (italic kappa) max_time: .inf # not yet implemented - merit_error_coeff: 10 # initial penalty coefficient - trust_box_size: 1e-1 # current size of trust region (component-wise) + merit_error_coeff: 10 # initial penalty coefficient. [Research Paper] mu_0 + trust_box_size: 1e-1 # current size of trust region (component-wise). [Research Paper] s problem_info: basic_info: n_steps: 20 # 2 * steps_per_phase dt_upper_lim: 2.0 # The upper limit of 1/dt values allowed in the optimization dt_lower_lim: 100.0 # The lower limit of 1/dt values allowed in the optimization - start_fixed: true # if true, start pose is the current pose and the req.start_state is ignored + start_fixed: true # if true, start pose is the current pose at timestep = 0 # if false, the start pose is the one given by req.start_state use_time: flase # if false, it means the timestep is unit, meaning x1-x0 is the velocity for example # if true, then cost_infos ro cnt_infos should have TT_USE_TIME for their term_type @@ -26,23 +26,25 @@ problem_info: # 1 = AUTO_SOLVER, 2 = BPMPD, 3 = OSQP, 4 = QPOASES, 5 = GUROBI init_info: - type: 2 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ + type: 3 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ # request.start_state should be provided for JOINT_INTERPOLATED and GIVEN_TRAJ dt: 0.5 joint_pos_term_info: - start_pos: + start_pos: # from req.start_state name: start_pos - first_timestep: 0 # First time step to which the term is applied. - last_timestep: 0 # Last time step to which the term is applied. n_steps - 1 + first_timestep: 10 # First time step to which the term is applied. + last_timestep: 10 # Last time step to which the term is applied. + # if start_fixed is trure then we can not set the first_timestep to 0 for start_pos as it is going + # to be ignored and only the current pose would be the constraint at timestep = 0. term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME middle_pos: name: middle_pos - first_timestep: 10 # First time step to which the term is applied. - last_timestep: 10 # Last time step to which the term is applied. n_steps - 1 - term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME + first_timestep: 15 + last_timestep: 15 + term_type: 2 goal_pos: name: goal_pos - first_timestep: 19 # First time step to which the term is applied. - last_timestep: 19 # Last time step to which the term is applied. n_steps - 1 - term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME + first_timestep: 19 + last_timestep: 19 + term_type: 2 diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h index 96274cf9c7..51dac66b6a 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -4,38 +4,33 @@ #include +using namespace Eigen; +using namespace std; + namespace trajopt_interface { -/** - * @brief Extracts the vector part of quaternion - */ -inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& matrix) +Vector3d rotVec(const Matrix3d& m) { - Eigen::Quaterniond quaternion; - quaternion = matrix; - return Eigen::Vector3d(quaternion.x(), quaternion.y(), quaternion.z()); + Quaterniond q; + q = m; + return Vector3d(q.x(), q.y(), q.z()); } -/** - * @brief Appends b to a of type VectorXd - */ -inline Eigen::VectorXd concatVector(const Eigen::VectorXd& vector_a, const Eigen::VectorXd& vector_b) +VectorXd concat(const VectorXd& a, const VectorXd& b) { - Eigen::VectorXd out(vector_a.size() + vector_b.size()); - out.topRows(vector_a.size()) = vector_a; - out.middleRows(vector_a.size(), vector_b.size()) = vector_b; + VectorXd out(a.size() + b.size()); + out.topRows(a.size()) = a; + out.middleRows(a.size(), b.size()) = b; return out; } -/** - * @brief Appends b to a of type T - */ template -inline std::vector concatVector(const std::vector& vector_a, const std::vector& vector_b) +vector concat(const vector& a, const vector& b) { - std::vector out; - out.insert(out.end(), vector_a.begin(), vector_a.end()); - out.insert(out.end(), vector_b.begin(), vector_b.end()); + vector out; + vector x(a.size() + b.size()); + out.insert(out.end(), a.begin(), a.end()); + out.insert(out.end(), b.begin(), b.end()); return out; } @@ -52,7 +47,7 @@ struct CartPoseErrCalculator : public sco::VectorOfVector Eigen::Isometry3d tcp_; CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, - const std::string& link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + std::string link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) { } diff --git a/moveit_planners/trajopt/include/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD similarity index 63% rename from moveit_planners/trajopt/include/kinematic_terms.h rename to moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD index c61052194a..96274cf9c7 100644 --- a/moveit_planners/trajopt/include/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD @@ -4,33 +4,38 @@ #include -using namespace Eigen; -using namespace std; - namespace trajopt_interface { -Vector3d rotVec(const Matrix3d& m) +/** + * @brief Extracts the vector part of quaternion + */ +inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& matrix) { - Quaterniond q; - q = m; - return Vector3d(q.x(), q.y(), q.z()); + Eigen::Quaterniond quaternion; + quaternion = matrix; + return Eigen::Vector3d(quaternion.x(), quaternion.y(), quaternion.z()); } -VectorXd concat(const VectorXd& a, const VectorXd& b) +/** + * @brief Appends b to a of type VectorXd + */ +inline Eigen::VectorXd concatVector(const Eigen::VectorXd& vector_a, const Eigen::VectorXd& vector_b) { - VectorXd out(a.size() + b.size()); - out.topRows(a.size()) = a; - out.middleRows(a.size(), b.size()) = b; + Eigen::VectorXd out(vector_a.size() + vector_b.size()); + out.topRows(vector_a.size()) = vector_a; + out.middleRows(vector_a.size(), vector_b.size()) = vector_b; return out; } +/** + * @brief Appends b to a of type T + */ template -vector concat(const vector& a, const vector& b) +inline std::vector concatVector(const std::vector& vector_a, const std::vector& vector_b) { - vector out; - vector x(a.size() + b.size()); - out.insert(out.end(), a.begin(), a.end()); - out.insert(out.end(), b.begin(), b.end()); + std::vector out; + out.insert(out.end(), vector_a.begin(), vector_a.end()); + out.insert(out.end(), vector_b.begin(), vector_b.end()); return out; } @@ -47,7 +52,7 @@ struct CartPoseErrCalculator : public sco::VectorOfVector Eigen::Isometry3d tcp_; CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, - std::string link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + const std::string& link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) { } @@ -85,4 +90,4 @@ struct JointVelJacobianCalculator : sco::MatrixOfVector Eigen::MatrixXd operator()(const Eigen::VectorXd& var_vals) const; }; -} // namespace trajopt +} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index 825c82262d..dbb9c040e5 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -112,7 +112,7 @@ struct InitInfo /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used to create initialization matrix. We need to give the goal information to this init info */ - trajopt::TrajArray data; + trajopt::TrajArray data; // This data type does not seem correct, it should be of type VectorXd // Eigen::VectorXd data_vec; // trajopt::TrajArray data_trajectory; /** @brief Default value the final column of the optimization is initialized too if time is being used */ @@ -122,7 +122,7 @@ struct InitInfo /** When cost or constraint element of JSON doc is read, one of these guys gets constructed to hold the parameters. -Then it later gets converted to a Cost object by the addObjectiveTerms method +Then it later gets converted to a Cost object by the hatch method */ struct TermInfo { @@ -133,7 +133,7 @@ struct TermInfo return supported_term_types_; } // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void addObjectiveTerms(TrajOptProblem& prob) = 0; + virtual void hatch(TrajOptProblem& prob) = 0; static TermInfoPtr fromName(const std::string& type); @@ -141,7 +141,7 @@ struct TermInfo * Registers a user-defined TermInfo so you can use your own cost * see function RegisterMakers.cpp */ - using MakerFunc = TermInfoPtr (*)(void); + typedef TermInfoPtr (*MakerFunc)(void); static void RegisterMaker(const std::string& type, MakerFunc); virtual ~TermInfo() = default; @@ -152,7 +152,7 @@ struct TermInfo } private: - static std::map name_to_maker_; + static std::map name2maker; int supported_term_types_; }; @@ -168,10 +168,11 @@ struct ProblemInfo planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) - : planning_scene(ps), planning_group_name(pg) + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) : planning_scene(ps), planning_group_name(pg) { } + +private: }; /** @@ -187,38 +188,32 @@ class TrajOptProblem : public sco::OptProb /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ sco::VarVector GetVarRow(int i, int start_col, int num_col) { - return matrix_traj_vars.rblock(i, start_col, num_col); + return m_traj_vars.rblock(i, start_col, num_col); } /** @brief Returns the values of all joints for the specified timestep i.*/ sco::VarVector GetVarRow(int i) { - return matrix_traj_vars.row(i); + return m_traj_vars.row(i); } /** @brief Returns the value of the specified joint j for the specified timestep i.*/ sco::Var& GetVar(int i, int j) { - return matrix_traj_vars.at(i, j); + return m_traj_vars.at(i, j); } trajopt::VarArray& GetVars() { - return matrix_traj_vars; + return m_traj_vars; } /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ int GetNumSteps() { - return matrix_traj_vars.rows(); + return m_traj_vars.rows(); } /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. * Note that this is not necessarily the same as the kinematic DOF.*/ int GetNumDOF() { - return matrix_traj_vars.cols(); - } - /** @brief Returns the kinematic DOF of the active joint model group - */ - int GetActiveGroupNumDOF() - { - return dof_; + return m_traj_vars.cols(); } planning_scene::PlanningSceneConstPtr GetPlanningScene() { @@ -226,11 +221,11 @@ class TrajOptProblem : public sco::OptProb } void SetInitTraj(const trajopt::TrajArray& x) { - matrix_init_traj = x; + m_init_traj = x; } trajopt::TrajArray GetInitTraj() { - return matrix_init_traj; + return m_init_traj; } // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); /** @brief Returns TrajOptProb.has_time */ @@ -248,12 +243,10 @@ class TrajOptProblem : public sco::OptProb /** @brief If true, the last column in the optimization matrix will be 1/dt */ bool has_time; /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ - trajopt::VarArray matrix_traj_vars; + trajopt::VarArray m_traj_vars; planning_scene::PlanningSceneConstPtr planning_scene_; std::string planning_group_; - /** @brief Kinematic DOF of the active joint model group */ - int dof_; - trajopt::TrajArray matrix_init_traj; + trajopt::TrajArray m_init_traj; }; /** @brief This term is used when the goal frame is fixed in cartesian space @@ -282,7 +275,7 @@ struct CartPoseTermInfo : public TermInfo /** @brief Used to add term to pci from json */ // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; + void hatch(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -322,7 +315,7 @@ struct JointPoseTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; + void hatch(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -352,7 +345,7 @@ struct JointVelTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; + void hatch(TrajOptProblem& prob) override; static TermInfoPtr create() { diff --git a/moveit_planners/trajopt/include/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD similarity index 88% rename from moveit_planners/trajopt/include/problem_description.h rename to moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD index 8d1bd605e1..825c82262d 100644 --- a/moveit_planners/trajopt/include/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD @@ -49,6 +49,9 @@ MOVEIT_CLASS_FORWARD(JointPoseTermInfo); struct CartPoseTermInfo; MOVEIT_CLASS_FORWARD(CartPoseTermInfo); +struct JointVelTermInfo; +MOVEIT_CLASS_FORWARD(JointVelTermInfo); + struct ProblemInfo; TrajOptProblemPtr ConstructProblem(const ProblemInfo&); @@ -109,9 +112,9 @@ struct InitInfo /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used to create initialization matrix. We need to give the goal information to this init info */ - //trajopt::TrajArray data; This data type does not seem correct, it should be of type VectorXd - Eigen::VectorXd end_pos; - trajopt::TrajArray start_to_end_trajectory; + trajopt::TrajArray data; + // Eigen::VectorXd data_vec; + // trajopt::TrajArray data_trajectory; /** @brief Default value the final column of the optimization is initialized too if time is being used */ double dt = 1.0; }; @@ -119,7 +122,7 @@ struct InitInfo /** When cost or constraint element of JSON doc is read, one of these guys gets constructed to hold the parameters. -Then it later gets converted to a Cost object by the hatch method +Then it later gets converted to a Cost object by the addObjectiveTerms method */ struct TermInfo { @@ -130,7 +133,7 @@ struct TermInfo return supported_term_types_; } // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void hatch(TrajOptProblem& prob) = 0; + virtual void addObjectiveTerms(TrajOptProblem& prob) = 0; static TermInfoPtr fromName(const std::string& type); @@ -138,7 +141,7 @@ struct TermInfo * Registers a user-defined TermInfo so you can use your own cost * see function RegisterMakers.cpp */ - typedef TermInfoPtr (*MakerFunc)(void); + using MakerFunc = TermInfoPtr (*)(void); static void RegisterMaker(const std::string& type, MakerFunc); virtual ~TermInfo() = default; @@ -149,7 +152,7 @@ struct TermInfo } private: - static std::map name2maker; + static std::map name_to_maker_; int supported_term_types_; }; @@ -165,12 +168,10 @@ struct ProblemInfo planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) : planning_scene(ps), planning_group_name(pg) + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) + : planning_scene(ps), planning_group_name(pg) { } - -private: - }; /** @@ -186,32 +187,38 @@ class TrajOptProblem : public sco::OptProb /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ sco::VarVector GetVarRow(int i, int start_col, int num_col) { - return m_traj_vars.rblock(i, start_col, num_col); + return matrix_traj_vars.rblock(i, start_col, num_col); } /** @brief Returns the values of all joints for the specified timestep i.*/ sco::VarVector GetVarRow(int i) { - return m_traj_vars.row(i); + return matrix_traj_vars.row(i); } /** @brief Returns the value of the specified joint j for the specified timestep i.*/ sco::Var& GetVar(int i, int j) { - return m_traj_vars.at(i, j); + return matrix_traj_vars.at(i, j); } trajopt::VarArray& GetVars() { - return m_traj_vars; + return matrix_traj_vars; } /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ int GetNumSteps() { - return m_traj_vars.rows(); + return matrix_traj_vars.rows(); } /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. * Note that this is not necessarily the same as the kinematic DOF.*/ int GetNumDOF() { - return m_traj_vars.cols(); + return matrix_traj_vars.cols(); + } + /** @brief Returns the kinematic DOF of the active joint model group + */ + int GetActiveGroupNumDOF() + { + return dof_; } planning_scene::PlanningSceneConstPtr GetPlanningScene() { @@ -219,11 +226,11 @@ class TrajOptProblem : public sco::OptProb } void SetInitTraj(const trajopt::TrajArray& x) { - m_init_traj = x; + matrix_init_traj = x; } trajopt::TrajArray GetInitTraj() { - return m_init_traj; + return matrix_init_traj; } // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); /** @brief Returns TrajOptProb.has_time */ @@ -241,10 +248,12 @@ class TrajOptProblem : public sco::OptProb /** @brief If true, the last column in the optimization matrix will be 1/dt */ bool has_time; /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ - trajopt::VarArray m_traj_vars; + trajopt::VarArray matrix_traj_vars; planning_scene::PlanningSceneConstPtr planning_scene_; std::string planning_group_; - trajopt::TrajArray m_init_traj; + /** @brief Kinematic DOF of the active joint model group */ + int dof_; + trajopt::TrajArray matrix_init_traj; }; /** @brief This term is used when the goal frame is fixed in cartesian space @@ -273,7 +282,7 @@ struct CartPoseTermInfo : public TermInfo /** @brief Used to add term to pci from json */ // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -313,7 +322,7 @@ struct JointPoseTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -343,7 +352,7 @@ struct JointVelTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -352,6 +361,7 @@ struct JointVelTermInfo : public TermInfo } }; - void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, trajopt::TrajArray& init_traj); +void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, + trajopt::TrajArray& init_traj); } // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h index 74432fa83c..1837af5a9e 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h @@ -1,7 +1,7 @@ /********************************************************************* * Software License Agreement (BSD License) * - * Copyright (c) 2019, PickNik, LLC. + * Copyright (c) 2019, PickNik, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -33,13 +33,18 @@ *********************************************************************/ /* Author: Omid Heidari */ -#pragma once + +#ifndef TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H +#define TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H #include + #include -#include + #include "problem_description.h" +#include + namespace trajopt_interface { MOVEIT_CLASS_FORWARD(TrajOptInterface); @@ -63,15 +68,14 @@ class TrajOptInterface void setDefaultTrajOPtParams(); void setProblemInfoParam(ProblemInfo& problem_info); void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); - trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, - const std::vector& group_joint_names); ros::NodeHandle nh_; /// The ROS node handle sco::BasicTrustRegionSQPParameters params_; - std::vector optimizer_callbacks_; - TrajOptProblemPtr trajopt_problem_; - std::string name_; + std::vector callbacks_; + TrajOptProblemPtr prob_; }; void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); } + +#endif diff --git a/moveit_planners/trajopt/include/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD similarity index 83% rename from moveit_planners/trajopt/include/trajopt_interface.h rename to moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD index deabc02168..74432fa83c 100644 --- a/moveit_planners/trajopt/include/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD @@ -1,7 +1,7 @@ /********************************************************************* * Software License Agreement (BSD License) * - * Copyright (c) 2019, PickNik, Inc. + * Copyright (c) 2019, PickNik, LLC. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -33,17 +33,12 @@ *********************************************************************/ /* Author: Omid Heidari */ - -#ifndef TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H -#define TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H +#pragma once #include - #include - -#include "problem_description.h" - #include +#include "problem_description.h" namespace trajopt_interface { @@ -52,7 +47,7 @@ MOVEIT_CLASS_FORWARD(TrajOptInterface); class TrajOptInterface { public: - TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); + TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); const sco::BasicTrustRegionSQPParameters& getParams() const { @@ -60,8 +55,7 @@ class TrajOptInterface } bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, - const planning_interface::MotionPlanRequest& req, - moveit_msgs::MotionPlanDetailedResponse& res); + const planning_interface::MotionPlanRequest& req, moveit_msgs::MotionPlanDetailedResponse& res); protected: /** @brief Configure everything using the param server */ @@ -69,14 +63,15 @@ class TrajOptInterface void setDefaultTrajOPtParams(); void setProblemInfoParam(ProblemInfo& problem_info); void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); + trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, + const std::vector& group_joint_names); ros::NodeHandle nh_; /// The ROS node handle sco::BasicTrustRegionSQPParameters params_; - std::vector callbacks_; - TrajOptProblemPtr prob_; + std::vector optimizer_callbacks_; + TrajOptProblemPtr trajopt_problem_; + std::string name_; }; void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); } - -#endif diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h index 12676f57e7..cebbc4b6f6 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h @@ -1,9 +1,10 @@ -#pragma once +#ifndef TrajOpt_PLANNING_CONTEXT_H +#define TrajOpt_PLANNING_CONTEXT_H #include -#include -#include +#include "trajopt_interface/problem_description.h" +#include "trajopt_interface/trajopt_interface.h" namespace trajopt_interface { @@ -24,9 +25,12 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext bool terminate() override; void clear() override; +protected: private: moveit::core::RobotModelConstPtr robot_model_; TrajOptInterfacePtr trajopt_interface_; }; } // namespace trajopt_interface + +#endif // TrajOpt_PLANNING_CONTEXT_H diff --git a/moveit_planners/trajopt/include/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD similarity index 80% rename from moveit_planners/trajopt/include/trajopt_planning_context.h rename to moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD index 3a6497bcf8..12676f57e7 100644 --- a/moveit_planners/trajopt/include/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD @@ -1,11 +1,9 @@ -#ifndef TrajOpt_PLANNING_CONTEXT_H -#define TrajOpt_PLANNING_CONTEXT_H +#pragma once #include - -#include "problem_description.h" -#include "trajopt_interface.h" +#include +#include namespace trajopt_interface { @@ -26,12 +24,9 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext bool terminate() override; void clear() override; -protected: private: moveit::core::RobotModelConstPtr robot_model_; TrajOptInterfacePtr trajopt_interface_; }; } // namespace trajopt_interface - -#endif // TrajOpt_PLANNING_CONTEXT_H diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp index 5b3d48a1c2..5dd17985b2 100644 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ b/moveit_planners/trajopt/src/test_trajopt.cpp @@ -1,5 +1,4 @@ #include -#include "trajopt_planning_context.h" #include #include @@ -24,16 +23,11 @@ #include #include +#include "trajopt_interface/trajopt_planning_context.h" // This file is a test for using trajopt in MoveIt. The goal is to make different types of constraints in -// MotionPlanRequest -// and visualize the result using trajopt planner. +// MotionPlanRequest and visualize the result calculated by using trajopt planner. // Three cases: -// 1- joint constraint with start_fixed true, meaining current state of the robot is the initial state of trajectory. -// 2- joint constraint with start_fixed false, meainig more than one goal should be given. The robot jumps to the first -// goal -// and motion planning is done between first goal and second goal. -// 3- Cartesian constraint. int main(int argc, char** argv) { @@ -48,7 +42,7 @@ int main(int argc, char** argv) new robot_model_loader::RobotModelLoader("robot_description")); robot_model::RobotModelPtr robot_model = robot_model_loader->getModel(); - /* Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group*/ + // Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model)); current_state->setToDefaultValues(); @@ -56,16 +50,19 @@ int main(int argc, char** argv) const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); - // With the planning scene we create a planing scene monitor that - // monitors planning scene diffs and applys them to the planning scene + // With the planning scene we create a planing scene monitor planning_scene_monitor::PlanningSceneMonitorPtr psm( new planning_scene_monitor::PlanningSceneMonitor(planning_scene, robot_model_loader)); psm->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE); psm->startStateMonitor(); psm->startSceneMonitor(); - // set the start joint state - // ======================================================================================== + // res req + planning_interface::MotionPlanRequest req; + planning_interface::MotionPlanResponse res; + + // set start state + // ====================================================================================== // panda_arm joint limits: // -2.8973 2.8973 // -1.7628 1.7628 @@ -75,38 +72,54 @@ int main(int argc, char** argv) // -0.0175 3.7525 // -2.8973 2.8973 - std::vector start_joint_values = {0.4, 0.3, 0.5, -0.55, 0.88, 1.0, -0.075 }; + std::vector start_joint_values = { 0.4, 0.3, 0.5, -0.55, 0.88, 1.0, -0.075 }; robot_state::RobotStatePtr start_state(new robot_state::RobotState(robot_model)); start_state->setJointGroupPositions(joint_model_group, start_joint_values); start_state->update(); - // planning_scene->setCurrentState(*robot_state); - - // get the joint values of the start state - // std::vector tmp_joint_values; - // robot_state->copyJointGroupPositions(joint_model_group, tmp_joint_values); - // int r = 0; - // for (auto x : tmp_joint_values) - // { - // printf("===>>> joint: %s with start value: %f \n", joint_names[r].c_str(), x); - // ++r; - // } - - // printf("--- get the joint values from planning scene current state"); - // robot_state::RobotState current_state = planning_scene->getCurrentState(); - // std::vector tmp_j_values; - // current_state.copyJointGroupPositions(joint_model_group, tmp_j_values); - // r = 0; - // for (auto x : tmp_j_values) - // { - // printf("===>>> joint: %s with start value: %f \n", joint_names[r].c_str(), x); - // ++r; - // } - - - + req.start_state.joint_state.name = joint_names; + req.start_state.joint_state.position = start_joint_values; + req.goal_constraints.clear(); + req.group_name = PLANNING_GROUP; + ROS_INFO(" ==================================== 0"); + // set the middle and goal state and joints tolerance // ======================================================================================== + robot_state::RobotStatePtr middle_state(new robot_state::RobotState(robot_model)); + std::vector middle_joint_values = { 0.5, 0.4, 0.65, -0.75, 1.05, 1.25, -0.15 }; + middle_state->setJointGroupPositions(joint_model_group, middle_joint_values); + middle_state->update(); + moveit_msgs::Constraints joint_middle = + kinematic_constraints::constructGoalConstraints(*middle_state, joint_model_group); + req.goal_constraints.push_back(joint_middle); + req.goal_constraints[0].name = "middle_pos"; + // set joint tolerance + std::vector middle_joint_constraint = req.goal_constraints[0].joint_constraints; + for (int x = 0; x < middle_joint_constraint.size(); ++x) + { + ROS_INFO(" ======================================= joint position at goal: %f", + middle_joint_constraint[x].position); + req.goal_constraints[0].joint_constraints[x].tolerance_above = 0.001; + req.goal_constraints[0].joint_constraints[x].tolerance_below = 0.001; + } + robot_state::RobotStatePtr goal_state(new robot_state::RobotState(robot_model)); + std::vector goal_joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1 }; + goal_state->setJointGroupPositions(joint_model_group, goal_joint_values); + goal_state->update(); + moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(*goal_state, joint_model_group); + req.goal_constraints.push_back(joint_goal); + req.goal_constraints[1].name = "goal_pos"; + // set joint tolerance + std::vector goal_joint_constraint = req.goal_constraints[1].joint_constraints; + for (int x = 0; x < goal_joint_constraint.size(); ++x) + { + ROS_INFO(" ======================================= joint position at goal: %f", goal_joint_constraint[x].position); + req.goal_constraints[1].joint_constraints[x].tolerance_above = 0.001; + req.goal_constraints[1].joint_constraints[x].tolerance_below = 0.001; + } + + // Load planner + // ====================================================================================== while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) { ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); @@ -153,8 +166,6 @@ int main(int argc, char** argv) // Visualization // ======================================================================================== - // The package MoveItVisualTools provides many capabilties for visualizing objects, robots, - // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script namespace rvt = rviz_visual_tools; moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0", rviz_visual_tools::RVIZ_MARKER_TOPIC, psm); visual_tools.loadRobotStatePub("/display_robot_state"); @@ -177,51 +188,6 @@ int main(int argc, char** argv) /* We can also use visual_tools to wait for user input */ visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); - // res req - planning_interface::MotionPlanRequest req; - planning_interface::MotionPlanResponse res; - - req.start_state.joint_state.name = joint_names; - req.start_state.joint_state.position = start_joint_values; - - // set the goal joint state and joints tolerance - // ======================================================================================== - robot_state::RobotState goal_state(robot_model); - std::vector goal_joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1 }; - goal_state.setJointGroupPositions(joint_model_group, goal_joint_values); - moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(goal_state, joint_model_group); - req.goal_constraints.clear(); - req.goal_constraints.push_back(joint_goal); - req.group_name = PLANNING_GROUP; - req.goal_constraints[0].name = "goal_pos"; - - // set joint tolerance - std::vector goal_joint_constraint = req.goal_constraints[0].joint_constraints; - for (int x = 0; x < goal_joint_constraint.size(); ++x) - { - std::cout << "==>> joint position at goal " << goal_joint_constraint[x].position << std::endl; - req.goal_constraints[0].joint_constraints[x].tolerance_above = 0.1; - req.goal_constraints[0].joint_constraints[x].tolerance_below = 0.1; - } - - robot_state::RobotState middle_state(robot_model); - std::vector middle_joint_values = {0.5, 0.4, 0.65, -0.75, 1.05, 1.25, -0.15 }; - middle_state.setJointGroupPositions(joint_model_group, middle_joint_values); - middle_state.update(); - moveit_msgs::Constraints joint_middle = kinematic_constraints::constructGoalConstraints(middle_state, joint_model_group); - req.goal_constraints.push_back(joint_middle); - req.goal_constraints[1].name = "middle_pos"; - std::cout << "hereeeeeeeeeeeeeeeeeeeeeeee 1 " << req.goal_constraints[1].joint_constraints[0].position << std::endl; - std::vector middle_joint_constraint = req.goal_constraints[1].joint_constraints; - std::cout << "hereeeeeeeeeeeeeeeeeeeeeeee 2" << std::endl; - for (int x = 0; x < middle_joint_constraint.size(); ++x) - { - std::cout << "==>> joint position at middle " << middle_joint_constraint[x].position << std::endl; - req.goal_constraints[1].joint_constraints[x].tolerance_above = 0.1; - req.goal_constraints[1].joint_constraints[x].tolerance_below = 0.1; - } - - std::cout << "===>>> number of constraints in goal: " << req.goal_constraints.size() << std::endl; // planning context // ======================================================================================== planning_interface::PlanningContextPtr context = @@ -263,24 +229,10 @@ int main(int argc, char** argv) visual_tools.trigger(); display_publisher.publish(display_trajectory); - - std::cout << "===>>> group name:" << response.group_name << std::endl; - std::cout << "===>>> traj start joint name size: " << response.trajectory_start.joint_state.name.size() << std::endl; - std::cout << "===>>> traj start joint position size: " << response.trajectory_start.joint_state.position.size() - << std::endl; - - std::cout << "===>>> traj joint names size: " << response.trajectory.joint_trajectory.joint_names.size() << std::endl; - - for (int jn = 0; jn < response.trajectory.joint_trajectory.joint_names.size(); ++jn) - { - std::cout << "===>>> joint_" << jn << ": " << response.trajectory.joint_trajectory.joint_names[jn] << std::endl; - } - - const std::vector& str = joint_model_group->getLinkModelNames(); - printf("end effector name %s\n", str.back().c_str()); + ROS_INFO("end effector name %s\n", str.back().c_str()); - const Eigen::Affine3d& end_effector_transform_current = current_state->getGlobalLinkTransform(str.back()); + const Eigen::Affine3d& end_effector_transform_current = current_state->getGlobalLinkTransform(str.back()); geometry_msgs::PoseStamped pose_msg; pose_msg.header.stamp = ros::Time::now(); pose_msg.header.frame_id = robot_model->getModelFrame(); @@ -288,34 +240,30 @@ int main(int argc, char** argv) visual_tools.publishAxisLabeled(pose_msg.pose, "current"); visual_tools.publishText(text_pose, "current pose", rvt::WHITE, rvt::XLARGE); - visual_tools.trigger(); - const Eigen::Affine3d& end_effector_transform_start = start_state->getGlobalLinkTransform(str.back()); + const Eigen::Affine3d& end_effector_transform_start = start_state->getGlobalLinkTransform(str.back()); pose_msg.header.stamp = ros::Time::now(); pose_msg.header.frame_id = robot_model->getModelFrame(); pose_msg.pose = tf2::toMsg(end_effector_transform_start); visual_tools.publishAxisLabeled(pose_msg.pose, "start"); visual_tools.publishText(text_pose, "start pose", rvt::BLUE, rvt::XLARGE); - visual_tools.trigger(); - - const Eigen::Affine3d& end_effector_transform_middle = middle_state.getGlobalLinkTransform(str.back()); + const Eigen::Affine3d& end_effector_transform_middle = middle_state->getGlobalLinkTransform(str.back()); pose_msg.header.stamp = ros::Time::now(); pose_msg.header.frame_id = robot_model->getModelFrame(); pose_msg.pose = tf2::toMsg(end_effector_transform_middle); visual_tools.publishAxisLabeled(pose_msg.pose, "middle"); - visual_tools.publishText(text_pose, "middle pose", rvt::BLUE, rvt::XLARGE); - visual_tools.trigger(); + visual_tools.publishText(text_pose, "middle pose", rvt::RED, rvt::XLARGE); - const Eigen::Affine3d& end_effector_transform_goal = goal_state.getGlobalLinkTransform(str.back()); + const Eigen::Affine3d& end_effector_transform_goal = goal_state->getGlobalLinkTransform(str.back()); pose_msg.header.stamp = ros::Time::now(); pose_msg.header.frame_id = robot_model->getModelFrame(); pose_msg.pose = tf2::toMsg(end_effector_transform_goal); visual_tools.publishAxisLabeled(pose_msg.pose, "goal"); - visual_tools.publishText(text_pose, "goal pose", rvt::BLUE, rvt::XLARGE); + visual_tools.publishText(text_pose, "goal pose", rvt::WHITE, rvt::XLARGE); visual_tools.trigger(); visual_tools.prompt("Press 'next' to finish demo \n"); diff --git a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp index a2b9e1f03b..5356e9801b 100644 --- a/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp +++ b/moveit_setup_assistant/src/widgets/configuration_files_widget.cpp @@ -374,18 +374,6 @@ bool ConfigurationFilesWidget::loadGenFiles() file.write_on_changes = 0; gen_files_.push_back(file); - // trajopt_planning_pipeline.launch - // -------------------------------------------------------------------------------------- - file.file_name_ = "trajopt_planning_pipeline.launch.xml"; - file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); - template_path = config_data_->appendPaths(template_launch_path, file.file_name_); - file.description_ = "Intended to be included in other launch files that require the TrajOpt planning plugin. Defines " - "the proper plugin name on the parameter server and a default selection of planning request " - "adapters."; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); - file.write_on_changes = 0; - gen_files_.push_back(file); - // chomp_planning_pipeline.launch // -------------------------------------------------------------------------------------- file.file_name_ = "chomp_planning_pipeline.launch.xml"; @@ -443,15 +431,6 @@ bool ConfigurationFilesWidget::loadGenFiles() file.write_on_changes = 0; gen_files_.push_back(file); - // run_benchmark_trajopt.launch -------------------------------------------------------------------------------------- - file.file_name_ = "run_benchmark_trajopt.launch"; - file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); - template_path = config_data_->appendPaths(template_launch_path, file.file_name_); - file.description_ = "Launch file for benchmarking TrajOpt planners"; - file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1); - file.write_on_changes = 0; - gen_files_.push_back(file); - // sensor_manager.launch -------------------------------------------------------------------------------------- file.file_name_ = "sensor_manager.launch.xml"; file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_); From c35c7d1ecdc54e01879737d208feccd379ca8906 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 1 Aug 2019 15:32:41 -0600 Subject: [PATCH 73/96] added kinematic DOF of the active joint model group to TrajOptProblem class added name_ for ROS_DEBUG_STREAM_NAMED addressed the comments moved launch file to moveit_tutorial moved yaml file to panda_moveit_config used bullet for collision checking --- .gitignore | 3 + moveit_planners/trajopt/config/setup.yaml | 50 ---- .../trajopt_interface/kinematic_terms.h | 31 +- .../trajopt_interface/problem_description.h | 38 ++- .../trajopt_interface/trajopt_interface.h | 8 +- .../trajopt_planning_context.h | 1 - .../trajopt/launch/test_trajopt_launch.launch | 33 --- moveit_planners/trajopt/src/test_trajopt.cpp | 270 ------------------ 8 files changed, 48 insertions(+), 386 deletions(-) delete mode 100644 moveit_planners/trajopt/config/setup.yaml delete mode 100644 moveit_planners/trajopt/launch/test_trajopt_launch.launch delete mode 100644 moveit_planners/trajopt/src/test_trajopt.cpp diff --git a/.gitignore b/.gitignore index cfc7f50ba4..917f3b56be 100644 --- a/.gitignore +++ b/.gitignore @@ -59,6 +59,9 @@ qtcreator-* #gdb *.gdb <<<<<<< HEAD +<<<<<<< HEAD ======= /moveit_planners/trajopt/launch/gdb_settings.gdb >>>>>>> addressed the comments +======= +>>>>>>> added kinematic DOF of the active joint model group to TrajOptProblem class diff --git a/moveit_planners/trajopt/config/setup.yaml b/moveit_planners/trajopt/config/setup.yaml deleted file mode 100644 index d3c8518cdd..0000000000 --- a/moveit_planners/trajopt/config/setup.yaml +++ /dev/null @@ -1,50 +0,0 @@ -trajopt_param: - improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step. [Research Paper] TrueImprove/ModelImprove > c - min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence. [Research Paper] xtol - min_approx_improve: 1e-4 # if model improves less than this, exit and report convergence - min_approx_improve_frac: -.Inf # if model improves less than this, exit and report convergence - max_iter: 100 # The max number of iterations - trust_shrink_ratio: 0.1 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao- - trust_expand_ratio: 1.5 # if improvement is less than improve_ratio_threshold, shrink trust region by this ratio. [Research Paper] tao+ - cnt_tolerance: 1e-4 # after convergence of penalty subproblem, if constraint violation is less than this, we're done. [Research Paper] ctol - max_merit_coeff_increases: 5 # number of times that we jack up penalty coefficient. [Reasearch Paper] Max iteration in PenaltyIteration loop - merit_coeff_increase_ratio: 10 # ratio that we increate coeff each time. [Researcy Paper] Penalty scaling factory (italic kappa) - max_time: .inf # not yet implemented - merit_error_coeff: 10 # initial penalty coefficient. [Research Paper] mu_0 - trust_box_size: 1e-1 # current size of trust region (component-wise). [Research Paper] s - -problem_info: - basic_info: - n_steps: 20 # 2 * steps_per_phase - dt_upper_lim: 2.0 # The upper limit of 1/dt values allowed in the optimization - dt_lower_lim: 100.0 # The lower limit of 1/dt values allowed in the optimization - start_fixed: true # if true, start pose is the current pose at timestep = 0 - # if false, the start pose is the one given by req.start_state - use_time: flase # if false, it means the timestep is unit, meaning x1-x0 is the velocity for example - # if true, then cost_infos ro cnt_infos should have TT_USE_TIME for their term_type - convex_solver: 1 # which convex solver to use - # 1 = AUTO_SOLVER, 2 = BPMPD, 3 = OSQP, 4 = QPOASES, 5 = GUROBI - - init_info: - type: 3 # 1 = STATIONARY, 2 = JOINT_INTERPOLATED, 3 = GIVEN_TRAJ - # request.start_state should be provided for JOINT_INTERPOLATED and GIVEN_TRAJ - dt: 0.5 - -joint_pos_term_info: - start_pos: # from req.start_state - name: start_pos - first_timestep: 10 # First time step to which the term is applied. - last_timestep: 10 # Last time step to which the term is applied. - # if start_fixed is trure then we can not set the first_timestep to 0 for start_pos as it is going - # to be ignored and only the current pose would be the constraint at timestep = 0. - term_type: 2 # 1 = TT_COST, 2 = TT_CNT, 3 = TT_USE_TIME - middle_pos: - name: middle_pos - first_timestep: 15 - last_timestep: 15 - term_type: 2 - goal_pos: - name: goal_pos - first_timestep: 19 - last_timestep: 19 - term_type: 2 diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h index 51dac66b6a..9a9a8a5d38 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -4,31 +4,38 @@ #include -using namespace Eigen; -using namespace std; - namespace trajopt_interface { -Vector3d rotVec(const Matrix3d& m) + +/** + * @brief Extracts the vector part of quaternion + */ +inline Eigen::Vector3d rotVec(const Eigen::Matrix3d& m) { - Quaterniond q; + Eigen::Quaterniond q; q = m; - return Vector3d(q.x(), q.y(), q.z()); + return Eigen::Vector3d(q.x(), q.y(), q.z()); } -VectorXd concat(const VectorXd& a, const VectorXd& b) +/** + * @brief Appends b to a of type VectorXd + */ +inline Eigen::VectorXd concat(const Eigen::VectorXd& a, const Eigen::VectorXd& b) { - VectorXd out(a.size() + b.size()); + Eigen::VectorXd out(a.size() + b.size()); out.topRows(a.size()) = a; out.middleRows(a.size(), b.size()) = b; return out; } +/** + * @brief Appends b to a of type T + */ template -vector concat(const vector& a, const vector& b) +std::vector concat(const std::vector& a, const std::vector& b) { - vector out; - vector x(a.size() + b.size()); + std::vector out; + std::vector x(a.size() + b.size()); out.insert(out.end(), a.begin(), a.end()); out.insert(out.end(), b.begin(), b.end()); return out; @@ -47,7 +54,7 @@ struct CartPoseErrCalculator : public sco::VectorOfVector Eigen::Isometry3d tcp_; CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, - std::string link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) + const std::string& link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) { } diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index dbb9c040e5..982862bea6 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -141,7 +141,7 @@ struct TermInfo * Registers a user-defined TermInfo so you can use your own cost * see function RegisterMakers.cpp */ - typedef TermInfoPtr (*MakerFunc)(void); + using MakerFunc = TermInfoPtr (*)(void); static void RegisterMaker(const std::string& type, MakerFunc); virtual ~TermInfo() = default; @@ -152,7 +152,7 @@ struct TermInfo } private: - static std::map name2maker; + static std::map name_to_maker_; int supported_term_types_; }; @@ -168,11 +168,9 @@ struct ProblemInfo planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, std::string pg) : planning_scene(ps), planning_group_name(pg) + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) : planning_scene(ps), planning_group_name(pg) { } - -private: }; /** @@ -188,32 +186,38 @@ class TrajOptProblem : public sco::OptProb /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ sco::VarVector GetVarRow(int i, int start_col, int num_col) { - return m_traj_vars.rblock(i, start_col, num_col); + return matrix_traj_vars.rblock(i, start_col, num_col); } /** @brief Returns the values of all joints for the specified timestep i.*/ sco::VarVector GetVarRow(int i) { - return m_traj_vars.row(i); + return matrix_traj_vars.row(i); } /** @brief Returns the value of the specified joint j for the specified timestep i.*/ sco::Var& GetVar(int i, int j) { - return m_traj_vars.at(i, j); + return matrix_traj_vars.at(i, j); } trajopt::VarArray& GetVars() { - return m_traj_vars; + return matrix_traj_vars; } /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ int GetNumSteps() { - return m_traj_vars.rows(); + return matrix_traj_vars.rows(); } /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. * Note that this is not necessarily the same as the kinematic DOF.*/ int GetNumDOF() { - return m_traj_vars.cols(); + return matrix_traj_vars.cols(); + } + /** @brief Returns the kinematic DOF of the active joint model group + */ + int GetActiveGroupNumDOF() + { + return dof_; } planning_scene::PlanningSceneConstPtr GetPlanningScene() { @@ -221,11 +225,11 @@ class TrajOptProblem : public sco::OptProb } void SetInitTraj(const trajopt::TrajArray& x) { - m_init_traj = x; + matrix_init_traj = x; } trajopt::TrajArray GetInitTraj() { - return m_init_traj; + return matrix_init_traj; } // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); /** @brief Returns TrajOptProb.has_time */ @@ -243,10 +247,12 @@ class TrajOptProblem : public sco::OptProb /** @brief If true, the last column in the optimization matrix will be 1/dt */ bool has_time; /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ - trajopt::VarArray m_traj_vars; + trajopt::VarArray matrix_traj_vars; planning_scene::PlanningSceneConstPtr planning_scene_; std::string planning_group_; - trajopt::TrajArray m_init_traj; + /** @brief Kinematic DOF of the active joint model group */ + int dof_; + trajopt::TrajArray matrix_init_traj; }; /** @brief This term is used when the goal frame is fixed in cartesian space @@ -354,6 +360,8 @@ struct JointVelTermInfo : public TermInfo } }; + + void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, trajopt::TrajArray& init_traj); diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h index 1837af5a9e..b84acd976c 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h @@ -1,7 +1,7 @@ /********************************************************************* * Software License Agreement (BSD License) * - * Copyright (c) 2019, PickNik, Inc. + * Copyright (c) 2019, PickNik, LLC. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -38,12 +38,9 @@ #define TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H #include - #include - -#include "problem_description.h" - #include +#include "problem_description.h" namespace trajopt_interface { @@ -73,6 +70,7 @@ class TrajOptInterface sco::BasicTrustRegionSQPParameters params_; std::vector callbacks_; TrajOptProblemPtr prob_; + std::string name_; }; void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h index cebbc4b6f6..8aaa209b24 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h @@ -25,7 +25,6 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext bool terminate() override; void clear() override; -protected: private: moveit::core::RobotModelConstPtr robot_model_; diff --git a/moveit_planners/trajopt/launch/test_trajopt_launch.launch b/moveit_planners/trajopt/launch/test_trajopt_launch.launch deleted file mode 100644 index f0d35bdeaa..0000000000 --- a/moveit_planners/trajopt/launch/test_trajopt_launch.launch +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/moveit_planners/trajopt/src/test_trajopt.cpp b/moveit_planners/trajopt/src/test_trajopt.cpp deleted file mode 100644 index 5dd17985b2..0000000000 --- a/moveit_planners/trajopt/src/test_trajopt.cpp +++ /dev/null @@ -1,270 +0,0 @@ -#include -#include - -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include -#include "moveit/planning_interface/planning_request.h" - -#include -#include - -#include -#include -#include -#include - -#include "trajopt_interface/trajopt_planning_context.h" - -// This file is a test for using trajopt in MoveIt. The goal is to make different types of constraints in -// MotionPlanRequest and visualize the result calculated by using trajopt planner. -// Three cases: - -int main(int argc, char** argv) -{ - const std::string node_name = "trajopot_planning_tutorial"; - ros::init(argc, argv, node_name); - ros::AsyncSpinner spinner(1); - spinner.start(); - ros::NodeHandle node_handle("~"); - - const std::string PLANNING_GROUP = "panda_arm"; - robot_model_loader::RobotModelLoaderPtr robot_model_loader( - new robot_model_loader::RobotModelLoader("robot_description")); - robot_model::RobotModelPtr robot_model = robot_model_loader->getModel(); - - // Create a RobotState and JointModelGroup to keep track of the current robot pose and planning group - robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model)); - current_state->setToDefaultValues(); - - const robot_state::JointModelGroup* joint_model_group = current_state->getJointModelGroup(PLANNING_GROUP); - const std::vector& joint_names = joint_model_group->getActiveJointModelNames(); - planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); - - // With the planning scene we create a planing scene monitor - planning_scene_monitor::PlanningSceneMonitorPtr psm( - new planning_scene_monitor::PlanningSceneMonitor(planning_scene, robot_model_loader)); - psm->startPublishingPlanningScene(planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE); - psm->startStateMonitor(); - psm->startSceneMonitor(); - - // res req - planning_interface::MotionPlanRequest req; - planning_interface::MotionPlanResponse res; - - // set start state - // ====================================================================================== - // panda_arm joint limits: - // -2.8973 2.8973 - // -1.7628 1.7628 - // -2.8973 2.8973 - // -3.0718 -0.0698 - // -2.8973 2.8973 - // -0.0175 3.7525 - // -2.8973 2.8973 - - std::vector start_joint_values = { 0.4, 0.3, 0.5, -0.55, 0.88, 1.0, -0.075 }; - robot_state::RobotStatePtr start_state(new robot_state::RobotState(robot_model)); - start_state->setJointGroupPositions(joint_model_group, start_joint_values); - start_state->update(); - - req.start_state.joint_state.name = joint_names; - req.start_state.joint_state.position = start_joint_values; - req.goal_constraints.clear(); - req.group_name = PLANNING_GROUP; - ROS_INFO(" ==================================== 0"); - // set the middle and goal state and joints tolerance - // ======================================================================================== - robot_state::RobotStatePtr middle_state(new robot_state::RobotState(robot_model)); - std::vector middle_joint_values = { 0.5, 0.4, 0.65, -0.75, 1.05, 1.25, -0.15 }; - middle_state->setJointGroupPositions(joint_model_group, middle_joint_values); - middle_state->update(); - moveit_msgs::Constraints joint_middle = - kinematic_constraints::constructGoalConstraints(*middle_state, joint_model_group); - req.goal_constraints.push_back(joint_middle); - req.goal_constraints[0].name = "middle_pos"; - // set joint tolerance - std::vector middle_joint_constraint = req.goal_constraints[0].joint_constraints; - for (int x = 0; x < middle_joint_constraint.size(); ++x) - { - ROS_INFO(" ======================================= joint position at goal: %f", - middle_joint_constraint[x].position); - req.goal_constraints[0].joint_constraints[x].tolerance_above = 0.001; - req.goal_constraints[0].joint_constraints[x].tolerance_below = 0.001; - } - - robot_state::RobotStatePtr goal_state(new robot_state::RobotState(robot_model)); - std::vector goal_joint_values = { 0.8, 0.7, 1, -1.3, 1.9, 2.2, -0.1 }; - goal_state->setJointGroupPositions(joint_model_group, goal_joint_values); - goal_state->update(); - moveit_msgs::Constraints joint_goal = kinematic_constraints::constructGoalConstraints(*goal_state, joint_model_group); - req.goal_constraints.push_back(joint_goal); - req.goal_constraints[1].name = "goal_pos"; - // set joint tolerance - std::vector goal_joint_constraint = req.goal_constraints[1].joint_constraints; - for (int x = 0; x < goal_joint_constraint.size(); ++x) - { - ROS_INFO(" ======================================= joint position at goal: %f", goal_joint_constraint[x].position); - req.goal_constraints[1].joint_constraints[x].tolerance_above = 0.001; - req.goal_constraints[1].joint_constraints[x].tolerance_below = 0.001; - } - - // Load planner - // ====================================================================================== - while (!psm->getStateMonitor()->haveCompleteState() && ros::ok()) - { - ROS_INFO_STREAM_THROTTLE_NAMED(1, node_name, "Waiting for complete state from topic "); - } - // We will now construct a loader to load a planner, by name. - // Note that we are using the ROS pluginlib library here. - boost::scoped_ptr> planner_plugin_loader; - planning_interface::PlannerManagerPtr planner_instance; - - std::string planner_plugin_name; - - planner_plugin_name = "trajopt_interface/TrajOptPlanner"; - node_handle.setParam("planning_plugin", planner_plugin_name); - - // making sure to catch all exceptions. - if (!node_handle.getParam("planning_plugin", planner_plugin_name)) - ROS_FATAL_STREAM("Could not find planner plugin name"); - try - { - planner_plugin_loader.reset(new pluginlib::ClassLoader( - "moveit_core", "planning_interface::PlannerManager")); - printf("===>>> planner_plugin_name: %s \n", planner_plugin_name.c_str()); - } - catch (pluginlib::PluginlibException& ex) - { - ROS_FATAL_STREAM("Exception while creating planning plugin loader " << ex.what()); - } - try - { - planner_instance.reset(planner_plugin_loader->createUnmanagedInstance(planner_plugin_name)); - if (!planner_instance->initialize(robot_model, node_handle.getNamespace())) // namespace ????. I dont use it - ROS_FATAL_STREAM("Could not initialize planner instance"); - ROS_INFO_STREAM("Using planning interface '" << planner_instance->getDescription() << "'"); - } - catch (pluginlib::PluginlibException& ex) - { - const std::vector& classes = planner_plugin_loader->getDeclaredClasses(); - std::stringstream ss; - for (std::size_t i = 0; i < classes.size(); ++i) - ss << classes[i] << " "; - ROS_ERROR_STREAM("Exception while loading planner '" << planner_plugin_name << "': " << ex.what() << std::endl - << "Available plugins: " << ss.str()); - } - - // Visualization - // ======================================================================================== - namespace rvt = rviz_visual_tools; - moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0", rviz_visual_tools::RVIZ_MARKER_TOPIC, psm); - visual_tools.loadRobotStatePub("/display_robot_state"); - visual_tools.enableBatchPublishing(); - visual_tools.deleteAllMarkers(); // clear all old markers - visual_tools.trigger(); - - /* Remote control is an introspection tool that allows users to step through a high level script - via buttons and keyboard shortcuts in RViz */ - visual_tools.loadRemoteControl(); - - /* RViz provides many types of markers, in this demo we will use text, cylinders, and spheres*/ - Eigen::Isometry3d text_pose = Eigen::Isometry3d::Identity(); - text_pose.translation().z() = 1.75; - visual_tools.publishText(text_pose, "Motion Planning API Demo", rvt::WHITE, rvt::XLARGE); - - /* Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations */ - visual_tools.trigger(); - - /* We can also use visual_tools to wait for user input */ - visual_tools.prompt("Press 'next' in the RvizVisualToolsGui window to start the demo"); - - // planning context - // ======================================================================================== - planning_interface::PlanningContextPtr context = - planner_instance->getPlanningContext(planning_scene, req, res.error_code_); - - context->solve(res); - if (res.error_code_.val != res.error_code_.SUCCESS) - { - ROS_ERROR("Could not compute plan successfully"); - return 0; - } - - visual_tools.prompt("Press 'next' to visualize the result"); - - // Visualize the result - // ======================================================================================== - ros::Publisher display_publisher = - node_handle.advertise("/move_group/display_planned_path", 1, true); - moveit_msgs::DisplayTrajectory display_trajectory; - - /* Visualize the trajectory */ - moveit_msgs::MotionPlanResponse response; - res.getMessage(response); - - for (int timestep_index = 0; timestep_index < response.trajectory.joint_trajectory.points.size(); ++timestep_index) - { - for (int joint_index = 0; - joint_index < response.trajectory.joint_trajectory.points[timestep_index].positions.size(); ++joint_index) - { - std::cout << response.trajectory.joint_trajectory.points[timestep_index].positions[joint_index] << " "; - } - std::cout << std::endl; - } - - display_trajectory.trajectory_start = response.trajectory_start; - display_trajectory.trajectory.push_back(response.trajectory); - - visual_tools.publishTrajectoryLine(display_trajectory.trajectory.back(), joint_model_group); - visual_tools.trigger(); - display_publisher.publish(display_trajectory); - - const std::vector& str = joint_model_group->getLinkModelNames(); - ROS_INFO("end effector name %s\n", str.back().c_str()); - - const Eigen::Affine3d& end_effector_transform_current = current_state->getGlobalLinkTransform(str.back()); - geometry_msgs::PoseStamped pose_msg; - pose_msg.header.stamp = ros::Time::now(); - pose_msg.header.frame_id = robot_model->getModelFrame(); - pose_msg.pose = tf2::toMsg(end_effector_transform_current); - - visual_tools.publishAxisLabeled(pose_msg.pose, "current"); - visual_tools.publishText(text_pose, "current pose", rvt::WHITE, rvt::XLARGE); - - const Eigen::Affine3d& end_effector_transform_start = start_state->getGlobalLinkTransform(str.back()); - pose_msg.header.stamp = ros::Time::now(); - pose_msg.header.frame_id = robot_model->getModelFrame(); - pose_msg.pose = tf2::toMsg(end_effector_transform_start); - - visual_tools.publishAxisLabeled(pose_msg.pose, "start"); - visual_tools.publishText(text_pose, "start pose", rvt::BLUE, rvt::XLARGE); - - const Eigen::Affine3d& end_effector_transform_middle = middle_state->getGlobalLinkTransform(str.back()); - pose_msg.header.stamp = ros::Time::now(); - pose_msg.header.frame_id = robot_model->getModelFrame(); - pose_msg.pose = tf2::toMsg(end_effector_transform_middle); - - visual_tools.publishAxisLabeled(pose_msg.pose, "middle"); - visual_tools.publishText(text_pose, "middle pose", rvt::RED, rvt::XLARGE); - - const Eigen::Affine3d& end_effector_transform_goal = goal_state->getGlobalLinkTransform(str.back()); - pose_msg.header.stamp = ros::Time::now(); - pose_msg.header.frame_id = robot_model->getModelFrame(); - pose_msg.pose = tf2::toMsg(end_effector_transform_goal); - - visual_tools.publishAxisLabeled(pose_msg.pose, "goal"); - visual_tools.publishText(text_pose, "goal pose", rvt::WHITE, rvt::XLARGE); - visual_tools.trigger(); - - visual_tools.prompt("Press 'next' to finish demo \n"); -} From 8fda2b88de6dd7743a95305702696fc4dc3951ab Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 8 Aug 2019 18:04:29 -0600 Subject: [PATCH 74/96] clang format --- .../trajopt/include/trajopt_interface/kinematic_terms.h | 1 - .../trajopt/include/trajopt_interface/problem_description.h | 5 ++--- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h index 9a9a8a5d38..5c60137b8e 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -6,7 +6,6 @@ namespace trajopt_interface { - /** * @brief Extracts the vector part of quaternion */ diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index 982862bea6..6c1fb3b4b9 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -168,7 +168,8 @@ struct ProblemInfo planning_scene::PlanningSceneConstPtr planning_scene; std::string planning_group_name; - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) : planning_scene(ps), planning_group_name(pg) + ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) + : planning_scene(ps), planning_group_name(pg) { } }; @@ -360,8 +361,6 @@ struct JointVelTermInfo : public TermInfo } }; - - void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, trajopt::TrajArray& init_traj); From a1ff679ebaa6c9a19a2cdc428a2a79111bf2a538 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Wed, 7 Aug 2019 09:01:56 -0600 Subject: [PATCH 75/96] Added comments about initial trajectory changed my email address renamed rotVec and concat added tesseract license --- .../trajopt/include/trajopt_interface/kinematic_terms.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h index 5c60137b8e..2796d0dffa 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -9,7 +9,7 @@ namespace trajopt_interface /** * @brief Extracts the vector part of quaternion */ -inline Eigen::Vector3d rotVec(const Eigen::Matrix3d& m) +inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& m) { Eigen::Quaterniond q; q = m; @@ -19,7 +19,7 @@ inline Eigen::Vector3d rotVec(const Eigen::Matrix3d& m) /** * @brief Appends b to a of type VectorXd */ -inline Eigen::VectorXd concat(const Eigen::VectorXd& a, const Eigen::VectorXd& b) +inline Eigen::VectorXd concatVector(const Eigen::VectorXd& a, const Eigen::VectorXd& b) { Eigen::VectorXd out(a.size() + b.size()); out.topRows(a.size()) = a; @@ -31,7 +31,7 @@ inline Eigen::VectorXd concat(const Eigen::VectorXd& a, const Eigen::VectorXd& b * @brief Appends b to a of type T */ template -std::vector concat(const std::vector& a, const std::vector& b) +std::vector concatVector(const std::vector& a, const std::vector& b) { std::vector out; std::vector x(a.size() + b.size()); From a8e22c4372f37aec58b99f55163735b238ca49cc Mon Sep 17 00:00:00 2001 From: omid1366 Date: Mon, 12 Aug 2019 09:45:00 -0600 Subject: [PATCH 76/96] applied Henning's comments --- .../trajopt/include/trajopt_interface/problem_description.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index 6c1fb3b4b9..60b1d6e356 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -112,7 +112,7 @@ struct InitInfo /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used to create initialization matrix. We need to give the goal information to this init info */ - trajopt::TrajArray data; // This data type does not seem correct, it should be of type VectorXd + trajopt::TrajArray data; // Eigen::VectorXd data_vec; // trajopt::TrajArray data_trajectory; /** @brief Default value the final column of the optimization is initialized too if time is being used */ From 6c29b6dda558072a9f3d70240e07f0eff009ee92 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Mon, 12 Aug 2019 13:33:07 -0600 Subject: [PATCH 77/96] added catkin ignore to ignore this package for now as it has dependencies. The next PR wont have any dependencies --- .gitignore | 7 ------- 1 file changed, 7 deletions(-) diff --git a/.gitignore b/.gitignore index 917f3b56be..808fe85341 100644 --- a/.gitignore +++ b/.gitignore @@ -58,10 +58,3 @@ qtcreator-* #gdb *.gdb -<<<<<<< HEAD -<<<<<<< HEAD -======= -/moveit_planners/trajopt/launch/gdb_settings.gdb ->>>>>>> addressed the comments -======= ->>>>>>> added kinematic DOF of the active joint model group to TrajOptProblem class From 9440d394df52f50798c9b2d07efcb10664dbcb54 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Tue, 13 Aug 2019 12:23:27 -0600 Subject: [PATCH 78/96] addressed the comments --- .../trajopt_interface/kinematic_terms.h | 23 +++++++++---------- .../trajopt_interface/trajopt_interface.h | 12 ++++------ .../trajopt_planning_context.h | 9 +++----- 3 files changed, 19 insertions(+), 25 deletions(-) diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h index 2796d0dffa..96274cf9c7 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h +++ b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h @@ -9,21 +9,21 @@ namespace trajopt_interface /** * @brief Extracts the vector part of quaternion */ -inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& m) +inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& matrix) { - Eigen::Quaterniond q; - q = m; - return Eigen::Vector3d(q.x(), q.y(), q.z()); + Eigen::Quaterniond quaternion; + quaternion = matrix; + return Eigen::Vector3d(quaternion.x(), quaternion.y(), quaternion.z()); } /** * @brief Appends b to a of type VectorXd */ -inline Eigen::VectorXd concatVector(const Eigen::VectorXd& a, const Eigen::VectorXd& b) +inline Eigen::VectorXd concatVector(const Eigen::VectorXd& vector_a, const Eigen::VectorXd& vector_b) { - Eigen::VectorXd out(a.size() + b.size()); - out.topRows(a.size()) = a; - out.middleRows(a.size(), b.size()) = b; + Eigen::VectorXd out(vector_a.size() + vector_b.size()); + out.topRows(vector_a.size()) = vector_a; + out.middleRows(vector_a.size(), vector_b.size()) = vector_b; return out; } @@ -31,12 +31,11 @@ inline Eigen::VectorXd concatVector(const Eigen::VectorXd& a, const Eigen::Vecto * @brief Appends b to a of type T */ template -std::vector concatVector(const std::vector& a, const std::vector& b) +inline std::vector concatVector(const std::vector& vector_a, const std::vector& vector_b) { std::vector out; - std::vector x(a.size() + b.size()); - out.insert(out.end(), a.begin(), a.end()); - out.insert(out.end(), b.begin(), b.end()); + out.insert(out.end(), vector_a.begin(), vector_a.end()); + out.insert(out.end(), vector_b.begin(), vector_b.end()); return out; } diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h index b84acd976c..74432fa83c 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h @@ -33,9 +33,7 @@ *********************************************************************/ /* Author: Omid Heidari */ - -#ifndef TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H -#define TRAJOPT_INTERFACE_TRAJOPT_INTERFACE_H +#pragma once #include #include @@ -65,15 +63,15 @@ class TrajOptInterface void setDefaultTrajOPtParams(); void setProblemInfoParam(ProblemInfo& problem_info); void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); + trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, + const std::vector& group_joint_names); ros::NodeHandle nh_; /// The ROS node handle sco::BasicTrustRegionSQPParameters params_; - std::vector callbacks_; - TrajOptProblemPtr prob_; + std::vector optimizer_callbacks_; + TrajOptProblemPtr trajopt_problem_; std::string name_; }; void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); } - -#endif diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h index 8aaa209b24..12676f57e7 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h +++ b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h @@ -1,10 +1,9 @@ -#ifndef TrajOpt_PLANNING_CONTEXT_H -#define TrajOpt_PLANNING_CONTEXT_H +#pragma once #include -#include "trajopt_interface/problem_description.h" -#include "trajopt_interface/trajopt_interface.h" +#include +#include namespace trajopt_interface { @@ -31,5 +30,3 @@ class TrajOptPlanningContext : public planning_interface::PlanningContext TrajOptInterfacePtr trajopt_interface_; }; } // namespace trajopt_interface - -#endif // TrajOpt_PLANNING_CONTEXT_H From c6889aad8c41ebd714e375c86e33bb9610c475ec Mon Sep 17 00:00:00 2001 From: omid1366 Date: Tue, 13 Aug 2019 14:36:49 -0600 Subject: [PATCH 79/96] renamed hatch to addObjectiveTerms --- .../include/trajopt_interface/problem_description.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h index 60b1d6e356..825c82262d 100644 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h +++ b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h @@ -122,7 +122,7 @@ struct InitInfo /** When cost or constraint element of JSON doc is read, one of these guys gets constructed to hold the parameters. -Then it later gets converted to a Cost object by the hatch method +Then it later gets converted to a Cost object by the addObjectiveTerms method */ struct TermInfo { @@ -133,7 +133,7 @@ struct TermInfo return supported_term_types_; } // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void hatch(TrajOptProblem& prob) = 0; + virtual void addObjectiveTerms(TrajOptProblem& prob) = 0; static TermInfoPtr fromName(const std::string& type); @@ -282,7 +282,7 @@ struct CartPoseTermInfo : public TermInfo /** @brief Used to add term to pci from json */ // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -322,7 +322,7 @@ struct JointPoseTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { @@ -352,7 +352,7 @@ struct JointVelTermInfo : public TermInfo } /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void hatch(TrajOptProblem& prob) override; + void addObjectiveTerms(TrajOptProblem& prob) override; static TermInfoPtr create() { From a7725390ddfa59f04353e7846ec05e7b036818fc Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 15 Aug 2019 10:00:37 -0600 Subject: [PATCH 80/96] addressed Dave's comments --- moveit_planners/trajopt/CATKIN_IGNORE | 0 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 moveit_planners/trajopt/CATKIN_IGNORE diff --git a/moveit_planners/trajopt/CATKIN_IGNORE b/moveit_planners/trajopt/CATKIN_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 From bb89f602cb4e45310c88a280382923b95983cacc Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 15 Aug 2019 10:34:31 -0600 Subject: [PATCH 81/96] added catkin_ignore --- moveit_planners/trajopt/CATKIN_IGNORE | 0 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 moveit_planners/trajopt/CATKIN_IGNORE diff --git a/moveit_planners/trajopt/CATKIN_IGNORE b/moveit_planners/trajopt/CATKIN_IGNORE new file mode 100644 index 0000000000..e69de29bb2 From 4df846aa3f33bcc2c3cd1db494ef59aa3697ff1b Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 15 Aug 2019 16:44:31 -0600 Subject: [PATCH 82/96] prepare for merge --- moveit_planners/trajopt/CATKIN_IGNORE | 0 .../include/trajopt}/kinematic_terms.h | 0 .../include/trajopt}/problem_description.h | 0 moveit_planners/trajopt/{ => trajopt}/src/kinematic_terms.cpp | 0 moveit_planners/trajopt/{ => trajopt}/src/problem_description.cpp | 0 moveit_planners/trajopt/{ => trajopt_interface}/CMakeLists.txt | 0 moveit_planners/trajopt/{ => trajopt_interface}/README.md | 0 .../include/trajopt_interface/trajopt_interface.h | 0 .../include/trajopt_interface/trajopt_planning_context.h | 0 moveit_planners/trajopt/{ => trajopt_interface}/package.xml | 0 .../trajopt/{ => trajopt_interface}/src/trajopt_interface.cpp | 0 .../{ => trajopt_interface}/src/trajopt_planner_manager.cpp | 0 .../{ => trajopt_interface}/src/trajopt_planning_context.cpp | 0 .../trajopt/{ => trajopt_interface}/test/trajectory_test.cpp | 0 .../trajopt/{ => trajopt_interface}/test/trajectory_test.test | 0 .../trajopt_interface_plugin_description.xml | 0 16 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 moveit_planners/trajopt/CATKIN_IGNORE rename moveit_planners/trajopt/{include/trajopt_interface => trajopt/include/trajopt}/kinematic_terms.h (100%) rename moveit_planners/trajopt/{include/trajopt_interface => trajopt/include/trajopt}/problem_description.h (100%) rename moveit_planners/trajopt/{ => trajopt}/src/kinematic_terms.cpp (100%) rename moveit_planners/trajopt/{ => trajopt}/src/problem_description.cpp (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/CMakeLists.txt (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/README.md (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/include/trajopt_interface/trajopt_interface.h (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/include/trajopt_interface/trajopt_planning_context.h (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/package.xml (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/src/trajopt_interface.cpp (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/src/trajopt_planner_manager.cpp (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/src/trajopt_planning_context.cpp (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/test/trajectory_test.cpp (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/test/trajectory_test.test (100%) rename moveit_planners/trajopt/{ => trajopt_interface}/trajopt_interface_plugin_description.xml (100%) diff --git a/moveit_planners/trajopt/CATKIN_IGNORE b/moveit_planners/trajopt/CATKIN_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h b/moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h similarity index 100% rename from moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h rename to moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h b/moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h similarity index 100% rename from moveit_planners/trajopt/include/trajopt_interface/problem_description.h rename to moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h diff --git a/moveit_planners/trajopt/src/kinematic_terms.cpp b/moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp similarity index 100% rename from moveit_planners/trajopt/src/kinematic_terms.cpp rename to moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp diff --git a/moveit_planners/trajopt/src/problem_description.cpp b/moveit_planners/trajopt/trajopt/src/problem_description.cpp similarity index 100% rename from moveit_planners/trajopt/src/problem_description.cpp rename to moveit_planners/trajopt/trajopt/src/problem_description.cpp diff --git a/moveit_planners/trajopt/CMakeLists.txt b/moveit_planners/trajopt/trajopt_interface/CMakeLists.txt similarity index 100% rename from moveit_planners/trajopt/CMakeLists.txt rename to moveit_planners/trajopt/trajopt_interface/CMakeLists.txt diff --git a/moveit_planners/trajopt/README.md b/moveit_planners/trajopt/trajopt_interface/README.md similarity index 100% rename from moveit_planners/trajopt/README.md rename to moveit_planners/trajopt/trajopt_interface/README.md diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h similarity index 100% rename from moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h rename to moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h similarity index 100% rename from moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h rename to moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h diff --git a/moveit_planners/trajopt/package.xml b/moveit_planners/trajopt/trajopt_interface/package.xml similarity index 100% rename from moveit_planners/trajopt/package.xml rename to moveit_planners/trajopt/trajopt_interface/package.xml diff --git a/moveit_planners/trajopt/src/trajopt_interface.cpp b/moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp similarity index 100% rename from moveit_planners/trajopt/src/trajopt_interface.cpp rename to moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp diff --git a/moveit_planners/trajopt/src/trajopt_planner_manager.cpp b/moveit_planners/trajopt/trajopt_interface/src/trajopt_planner_manager.cpp similarity index 100% rename from moveit_planners/trajopt/src/trajopt_planner_manager.cpp rename to moveit_planners/trajopt/trajopt_interface/src/trajopt_planner_manager.cpp diff --git a/moveit_planners/trajopt/src/trajopt_planning_context.cpp b/moveit_planners/trajopt/trajopt_interface/src/trajopt_planning_context.cpp similarity index 100% rename from moveit_planners/trajopt/src/trajopt_planning_context.cpp rename to moveit_planners/trajopt/trajopt_interface/src/trajopt_planning_context.cpp diff --git a/moveit_planners/trajopt/test/trajectory_test.cpp b/moveit_planners/trajopt/trajopt_interface/test/trajectory_test.cpp similarity index 100% rename from moveit_planners/trajopt/test/trajectory_test.cpp rename to moveit_planners/trajopt/trajopt_interface/test/trajectory_test.cpp diff --git a/moveit_planners/trajopt/test/trajectory_test.test b/moveit_planners/trajopt/trajopt_interface/test/trajectory_test.test similarity index 100% rename from moveit_planners/trajopt/test/trajectory_test.test rename to moveit_planners/trajopt/trajopt_interface/test/trajectory_test.test diff --git a/moveit_planners/trajopt/trajopt_interface_plugin_description.xml b/moveit_planners/trajopt/trajopt_interface/trajopt_interface_plugin_description.xml similarity index 100% rename from moveit_planners/trajopt/trajopt_interface_plugin_description.xml rename to moveit_planners/trajopt/trajopt_interface/trajopt_interface_plugin_description.xml From 010434a63f8ccc4e7ea0cc1e164bc814a43ee0e6 Mon Sep 17 00:00:00 2001 From: omid1366 Date: Thu, 15 Aug 2019 17:52:42 -0600 Subject: [PATCH 83/96] resolved conflicts --- .../trajopt_interface/kinematic_terms.h~HEAD | 93 -- .../problem_description.h~HEAD | 367 ------- .../trajopt_interface.h~HEAD | 77 -- .../trajopt_planning_context.h~HEAD | 32 - .../trajopt/trajopt/CMakeLists.txt | 70 ++ moveit_planners/trajopt/trajopt/LICENSE | 11 + .../trajopt/trajopt/include/trajopt/cache.hxx | 26 + .../trajopt/include/trajopt/common.hpp | 3 + .../trajopt/include/trajopt/kinematic_terms.h | 4 +- .../include/trajopt/problem_description.h | 8 +- .../include/trajopt/trajectory_costs.hpp | 533 ++++++++++ .../trajopt/include/trajopt/typedefs.hpp | 77 ++ .../trajopt/trajopt/include/trajopt/utils.hpp | 153 +++ moveit_planners/trajopt/trajopt/package.xml | 28 + .../trajopt/trajopt/src/kinematic_terms.cpp | 6 +- .../trajopt/src/problem_description.cpp | 9 +- .../trajopt/trajopt/src/trajectory_costs.cpp | 955 ++++++++++++++++++ moveit_planners/trajopt/trajopt/src/utils.cpp | 90 ++ .../trajopt/trajopt_interface/CMakeLists.txt | 37 +- .../trajopt/trajopt_interface/README.md | 2 +- .../trajopt_interface/trajopt_interface.h | 12 +- .../trajopt_planning_context.h | 2 +- .../trajopt/trajopt_interface/package.xml | 1 + .../src/trajopt_interface.cpp | 59 +- .../trajopt_sco/3rdpartylib/bpmpd_linux32.a | Bin 0 -> 532260 bytes .../trajopt_sco/3rdpartylib/bpmpd_linux64.a | Bin 0 -> 740972 bytes .../trajopt/trajopt_sco/CMakeLists.txt | 138 +++ moveit_planners/trajopt/trajopt_sco/LICENSE | 11 + .../cmake/Modules/FindGUROBI.cmake | 43 + .../cmake/Modules/FindqpOASES.cmake | 51 + .../include/trajopt_sco/bpmpd_interface.hpp | 40 + .../include/trajopt_sco/bpmpd_io.hpp | 168 +++ .../include/trajopt_sco/expr_op_overloads.hpp | 40 + .../include/trajopt_sco/expr_ops.hpp | 163 +++ .../include/trajopt_sco/expr_vec_ops.hpp | 30 + .../include/trajopt_sco/gurobi_interface.hpp | 53 + .../include/trajopt_sco/modeling.hpp | 239 +++++ .../include/trajopt_sco/modeling_utils.hpp | 108 ++ .../include/trajopt_sco/num_diff.hpp | 72 ++ .../include/trajopt_sco/optimizers.hpp | 128 +++ .../include/trajopt_sco/osqp_interface.hpp | 84 ++ .../include/trajopt_sco/qpoases_interface.hpp | 95 ++ .../include/trajopt_sco/sco_common.hpp | 52 + .../include/trajopt_sco/sco_fwd.hpp | 48 + .../include/trajopt_sco/solver_interface.hpp | 206 ++++ .../include/trajopt_sco/solver_utils.hpp | 154 +++ .../trajopt/trajopt_sco/package.xml | 17 + .../trajopt/trajopt_sco/src/bpmpd.par | 189 ++++ .../trajopt/trajopt_sco/src/bpmpd_caller.cpp | 102 ++ .../trajopt_sco/src/bpmpd_interface.cpp | 521 ++++++++++ .../trajopt/trajopt_sco/src/expr_ops.cpp | 103 ++ .../trajopt/trajopt_sco/src/expr_vec_ops.cpp | 12 + .../trajopt_sco/src/gurobi_interface.cpp | 306 ++++++ .../trajopt/trajopt_sco/src/modeling.cpp | 266 +++++ .../trajopt_sco/src/modeling_utils.cpp | 266 +++++ .../trajopt/trajopt_sco/src/num_diff.cpp | 118 +++ .../trajopt/trajopt_sco/src/optimizers.cpp | 491 +++++++++ .../trajopt_sco/src/osqp_interface.cpp | 270 +++++ .../trajopt_sco/src/qpoases_interface.cpp | 251 +++++ .../trajopt_sco/src/solver_interface.cpp | 305 ++++++ .../trajopt/trajopt_sco/src/solver_utils.cpp | 134 +++ .../trajopt_sco/test/small-problems-unit.cpp | 175 ++++ .../test/solver-interface-unit.cpp | 244 +++++ .../trajopt_sco/test/solver-utils-unit.cpp | 261 +++++ .../trajopt/trajopt_sco/test/unit.cpp | 10 + .../trajopt/trajopt_utils/CMakeLists.txt | 49 + moveit_planners/trajopt/trajopt_utils/LICENSE | 11 + .../include/trajopt_utils/basic_array.hpp | 102 ++ .../include/trajopt_utils/clock.hpp | 7 + .../include/trajopt_utils/config.hpp | 63 ++ .../trajopt_utils/eigen_conversions.hpp | 18 + .../include/trajopt_utils/eigen_slicing.hpp | 27 + .../include/trajopt_utils/interpolation.hpp | 48 + .../include/trajopt_utils/logging.hpp | 71 ++ .../include/trajopt_utils/macros.h | 71 ++ .../include/trajopt_utils/math.hpp | 10 + .../include/trajopt_utils/stl_to_string.hpp | 73 ++ .../include/trajopt_utils/vector_ops.hpp | 17 + .../trajopt/trajopt_utils/package.xml | 16 + .../trajopt/trajopt_utils/src/clock.cpp | 40 + .../trajopt/trajopt_utils/src/config.cpp | 27 + .../trajopt/trajopt_utils/src/logging.cpp | 54 + .../trajopt_utils/src/stl_to_string.cpp | 24 + .../trajopt_utils/src/test_logging.cpp | 12 + 84 files changed, 8708 insertions(+), 651 deletions(-) delete mode 100644 moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD delete mode 100644 moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD delete mode 100644 moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD delete mode 100644 moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD create mode 100644 moveit_planners/trajopt/trajopt/CMakeLists.txt create mode 100644 moveit_planners/trajopt/trajopt/LICENSE create mode 100644 moveit_planners/trajopt/trajopt/include/trajopt/cache.hxx create mode 100644 moveit_planners/trajopt/trajopt/include/trajopt/common.hpp create mode 100644 moveit_planners/trajopt/trajopt/include/trajopt/trajectory_costs.hpp create mode 100644 moveit_planners/trajopt/trajopt/include/trajopt/typedefs.hpp create mode 100644 moveit_planners/trajopt/trajopt/include/trajopt/utils.hpp create mode 100644 moveit_planners/trajopt/trajopt/package.xml create mode 100644 moveit_planners/trajopt/trajopt/src/trajectory_costs.cpp create mode 100644 moveit_planners/trajopt/trajopt/src/utils.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux32.a create mode 100644 moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux64.a create mode 100644 moveit_planners/trajopt/trajopt_sco/CMakeLists.txt create mode 100644 moveit_planners/trajopt/trajopt_sco/LICENSE create mode 100644 moveit_planners/trajopt/trajopt_sco/cmake/Modules/FindGUROBI.cmake create mode 100644 moveit_planners/trajopt/trajopt_sco/cmake/Modules/FindqpOASES.cmake create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/bpmpd_interface.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/bpmpd_io.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/expr_op_overloads.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/expr_ops.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/expr_vec_ops.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/gurobi_interface.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/modeling.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/modeling_utils.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/num_diff.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/optimizers.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/osqp_interface.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/qpoases_interface.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/sco_common.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/sco_fwd.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/solver_interface.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/include/trajopt_sco/solver_utils.hpp create mode 100644 moveit_planners/trajopt/trajopt_sco/package.xml create mode 100644 moveit_planners/trajopt/trajopt_sco/src/bpmpd.par create mode 100644 moveit_planners/trajopt/trajopt_sco/src/bpmpd_caller.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/bpmpd_interface.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/expr_ops.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/expr_vec_ops.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/gurobi_interface.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/modeling.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/modeling_utils.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/num_diff.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/optimizers.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/osqp_interface.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/qpoases_interface.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/solver_interface.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/src/solver_utils.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/test/small-problems-unit.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/test/solver-interface-unit.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/test/solver-utils-unit.cpp create mode 100644 moveit_planners/trajopt/trajopt_sco/test/unit.cpp create mode 100644 moveit_planners/trajopt/trajopt_utils/CMakeLists.txt create mode 100644 moveit_planners/trajopt/trajopt_utils/LICENSE create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/basic_array.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/clock.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/config.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/eigen_conversions.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/eigen_slicing.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/interpolation.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/logging.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/macros.h create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/math.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/stl_to_string.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/include/trajopt_utils/vector_ops.hpp create mode 100644 moveit_planners/trajopt/trajopt_utils/package.xml create mode 100644 moveit_planners/trajopt/trajopt_utils/src/clock.cpp create mode 100644 moveit_planners/trajopt/trajopt_utils/src/config.cpp create mode 100644 moveit_planners/trajopt/trajopt_utils/src/logging.cpp create mode 100644 moveit_planners/trajopt/trajopt_utils/src/stl_to_string.cpp create mode 100644 moveit_planners/trajopt/trajopt_utils/src/test_logging.cpp diff --git a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD b/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD deleted file mode 100644 index 96274cf9c7..0000000000 --- a/moveit_planners/trajopt/include/trajopt_interface/kinematic_terms.h~HEAD +++ /dev/null @@ -1,93 +0,0 @@ -#pragma once - -#include - -#include - -namespace trajopt_interface -{ -/** - * @brief Extracts the vector part of quaternion - */ -inline Eigen::Vector3d quaternionRotationVector(const Eigen::Matrix3d& matrix) -{ - Eigen::Quaterniond quaternion; - quaternion = matrix; - return Eigen::Vector3d(quaternion.x(), quaternion.y(), quaternion.z()); -} - -/** - * @brief Appends b to a of type VectorXd - */ -inline Eigen::VectorXd concatVector(const Eigen::VectorXd& vector_a, const Eigen::VectorXd& vector_b) -{ - Eigen::VectorXd out(vector_a.size() + vector_b.size()); - out.topRows(vector_a.size()) = vector_a; - out.middleRows(vector_a.size(), vector_b.size()) = vector_b; - return out; -} - -/** - * @brief Appends b to a of type T - */ -template -inline std::vector concatVector(const std::vector& vector_a, const std::vector& vector_b) -{ - std::vector out; - out.insert(out.end(), vector_a.begin(), vector_a.end()); - out.insert(out.end(), vector_b.begin(), vector_b.end()); - return out; -} - -/** - * @brief Used to calculate the error for StaticCartPoseTermInfo - * This is converted to a cost or constraint using TrajOptCostFromErrFunc or TrajOptConstraintFromErrFunc - */ -struct CartPoseErrCalculator : public sco::VectorOfVector -{ - EIGEN_MAKE_ALIGNED_OPERATOR_NEW - Eigen::Isometry3d target_pose_inv_; - planning_scene::PlanningSceneConstPtr planning_scene_; - std::string link_; - Eigen::Isometry3d tcp_; - - CartPoseErrCalculator(const Eigen::Isometry3d& pose, const planning_scene::PlanningSceneConstPtr planning_scene, - const std::string& link, Eigen::Isometry3d tcp = Eigen::Isometry3d::Identity()) - : target_pose_inv_(pose.inverse()), planning_scene_(planning_scene), link_(link), tcp_(tcp) - { - } - - Eigen::VectorXd operator()(const Eigen::VectorXd& dof_vals) const override; -}; - -// TODO(omid): The following should be added and adjusted from trajopt -// JointPosEqCost -// JointPosIneqCost -// JointPosEqConstraint -// JointPosIneqConstraint - -struct JointVelErrCalculator : sco::VectorOfVector -{ - /** @brief Velocity target */ - double target_; - /** @brief Upper tolerance */ - double upper_tol_; - /** @brief Lower tolerance */ - double lower_tol_; - JointVelErrCalculator() : target_(0.0), upper_tol_(0.0), lower_tol_(0.0) - { - } - JointVelErrCalculator(double target, double upper_tol, double lower_tol) - : target_(target), upper_tol_(upper_tol), lower_tol_(lower_tol) - { - } - - Eigen::VectorXd operator()(const Eigen::VectorXd& var_vals) const; -}; - -struct JointVelJacobianCalculator : sco::MatrixOfVector -{ - Eigen::MatrixXd operator()(const Eigen::VectorXd& var_vals) const; -}; - -} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD b/moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD deleted file mode 100644 index 825c82262d..0000000000 --- a/moveit_planners/trajopt/include/trajopt_interface/problem_description.h~HEAD +++ /dev/null @@ -1,367 +0,0 @@ -#pragma once -#include -#include -#include - -#include -#include - -#include - -namespace trajopt_interface -{ -/** -@brief Used to apply cost/constraint to joint-space velocity - -Term is applied to every step between first_step and last_step. It applies two limits, upper_limits/lower_limits, -to the joint velocity subject to the following cases. - -* term_type = TT_COST -** upper_limit = lower_limit = 0 - Cost is applied with a SQUARED error scaled for each joint by coeffs -** upper_limit != lower_limit - 2 hinge costs are applied scaled for each joint by coeffs. If velocity < upper_limit and -velocity > lower_limit, no penalty. - -* term_type = TT_CNT -** upper_limit = lower_limit = 0 - Equality constraint is applied -** upper_limit != lower_limit - 2 Inequality constraints are applied. These are both satisfied when velocity < -upper_limit and velocity > lower_limit - -Note: coeffs, upper_limits, and lower_limits are optional. If a term is not given it will default to 0 for all joints. -If one value is given, this will be broadcast to all joints. - -Note: Velocity is calculated numerically using forward finite difference - -\f{align*}{ - cost = \sum_{t=0}^{T-2} \sum_j c_j (x_{t+1,j} - x_{t,j})^2 -\f} -where j indexes over DOF, and \f$c_j\f$ are the coeffs. -*/ - -struct TermInfo; -MOVEIT_CLASS_FORWARD(TermInfo); - -class TrajOptProblem; -MOVEIT_CLASS_FORWARD(TrajOptProblem); - -struct JointPoseTermInfo; -MOVEIT_CLASS_FORWARD(JointPoseTermInfo); - -struct CartPoseTermInfo; -MOVEIT_CLASS_FORWARD(CartPoseTermInfo); - -struct JointVelTermInfo; -MOVEIT_CLASS_FORWARD(JointVelTermInfo); - -struct ProblemInfo; -TrajOptProblemPtr ConstructProblem(const ProblemInfo&); - -enum TermType -{ - TT_COST = 0x1, // 0000 0001 - TT_CNT = 0x2, // 0000 0010 - TT_USE_TIME = 0x4, // 0000 0100 -}; - -struct BasicInfo -{ - /** @brief If true, first time step is fixed with a joint level constraint - If this is false, the starting point of the trajectory will - not be the current position of the robot. The use case example is: if we are trying to execute a process like - sanding the critical part which is the actual process path not how we get to the start of the process path. So we - plan the - process path first leaving the start free to hopefully get the most optimal and then we plan from the current - location with - start fixed to the start of the process path. It depends on what we want the default behavior to be - */ - bool start_fixed; - /** @brief Number of time steps (rows) in the optimization matrix */ - int n_steps; - sco::IntVec dofs_fixed; // optional - sco::ModelType convex_solver; // which convex solver to use - - /** @brief If true, the last column in the optimization matrix will be 1/dt */ - bool use_time = false; - /** @brief The upper limit of 1/dt values allowed in the optimization*/ - double dt_upper_lim = 1.0; - /** @brief The lower limit of 1/dt values allowed in the optimization*/ - double dt_lower_lim = 1.0; -}; - -/** -Initialization info read from json -*/ -struct InitInfo -{ - /** @brief Methods of initializing the optimization matrix. This defines how robot moves from the current - state to the start state - - STATIONARY: Initializes all joint values to the initial value (the current value in the env) - JOINT_INTERPOLATED: Linearly interpolates between initial value and the joint position specified in InitInfo.data - GIVEN_TRAJ: Initializes the matrix to a given trajectory - - In all cases the dt column (if present) is appended the selected method is defined. - */ - enum Type - { - STATIONARY, - JOINT_INTERPOLATED, - GIVEN_TRAJ, - }; - /** @brief Specifies the type of initialization to use */ - Type type; - /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used - to create initialization matrix. We need to give the goal information to this init info - */ - trajopt::TrajArray data; - // Eigen::VectorXd data_vec; - // trajopt::TrajArray data_trajectory; - /** @brief Default value the final column of the optimization is initialized too if time is being used */ - double dt = 1.0; -}; - -/** -When cost or constraint element of JSON doc is read, one of these guys gets -constructed to hold the parameters. -Then it later gets converted to a Cost object by the addObjectiveTerms method -*/ -struct TermInfo -{ - std::string name; - int term_type; - int getSupportedTypes() - { - return supported_term_types_; - } - // virtual void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) = 0; - virtual void addObjectiveTerms(TrajOptProblem& prob) = 0; - - static TermInfoPtr fromName(const std::string& type); - - /** - * Registers a user-defined TermInfo so you can use your own cost - * see function RegisterMakers.cpp - */ - using MakerFunc = TermInfoPtr (*)(void); - static void RegisterMaker(const std::string& type, MakerFunc); - - virtual ~TermInfo() = default; - -protected: - TermInfo(int supported_term_types) : supported_term_types_(supported_term_types) - { - } - -private: - static std::map name_to_maker_; - int supported_term_types_; -}; - -struct ProblemInfo -{ -public: - BasicInfo basic_info; - sco::BasicTrustRegionSQPParameters opt_info; - std::vector cost_infos; - std::vector cnt_infos; - InitInfo init_info; - - planning_scene::PlanningSceneConstPtr planning_scene; - std::string planning_group_name; - - ProblemInfo(planning_scene::PlanningSceneConstPtr ps, const std::string& pg) - : planning_scene(ps), planning_group_name(pg) - { - } -}; - -/** - * Holds all the data for a trajectory optimization problem - * so you can modify it programmatically, e.g. add your own costs - */ -class TrajOptProblem : public sco::OptProb -{ -public: - TrajOptProblem(); - TrajOptProblem(const ProblemInfo& problem_info); - virtual ~TrajOptProblem() = default; - /** @brief Returns the values of the specified joints (start_col to num_col) for the specified timestep i.*/ - sco::VarVector GetVarRow(int i, int start_col, int num_col) - { - return matrix_traj_vars.rblock(i, start_col, num_col); - } - /** @brief Returns the values of all joints for the specified timestep i.*/ - sco::VarVector GetVarRow(int i) - { - return matrix_traj_vars.row(i); - } - /** @brief Returns the value of the specified joint j for the specified timestep i.*/ - sco::Var& GetVar(int i, int j) - { - return matrix_traj_vars.at(i, j); - } - trajopt::VarArray& GetVars() - { - return matrix_traj_vars; - } - /** @brief Returns the number of steps in the problem. This is the number of rows in the optimization matrix.*/ - int GetNumSteps() - { - return matrix_traj_vars.rows(); - } - /** @brief Returns the problem DOF. This is the number of columns in the optization matrix. - * Note that this is not necessarily the same as the kinematic DOF.*/ - int GetNumDOF() - { - return matrix_traj_vars.cols(); - } - /** @brief Returns the kinematic DOF of the active joint model group - */ - int GetActiveGroupNumDOF() - { - return dof_; - } - planning_scene::PlanningSceneConstPtr GetPlanningScene() - { - return planning_scene_; - } - void SetInitTraj(const trajopt::TrajArray& x) - { - matrix_init_traj = x; - } - trajopt::TrajArray GetInitTraj() - { - return matrix_init_traj; - } - // friend TrajOptProbPtr ConstructProblem(const ProblemConstructionInfo&); - /** @brief Returns TrajOptProb.has_time */ - bool GetHasTime() - { - return has_time; - } - /** @brief Sets TrajOptProb.has_time */ - void SetHasTime(bool tmp) - { - has_time = tmp; - } - -private: - /** @brief If true, the last column in the optimization matrix will be 1/dt */ - bool has_time; - /** @brief is the matrix holding the joint values of the trajectory for all timesteps */ - trajopt::VarArray matrix_traj_vars; - planning_scene::PlanningSceneConstPtr planning_scene_; - std::string planning_group_; - /** @brief Kinematic DOF of the active joint model group */ - int dof_; - trajopt::TrajArray matrix_init_traj; -}; - -/** @brief This term is used when the goal frame is fixed in cartesian space - - Set term_type == TT_COST or TT_CNT for cost or constraint. -*/ -struct CartPoseTermInfo : public TermInfo -{ - // EIGEN_MAKE_ALIGNED_OPERATOR_NEW - - /** @brief Timestep at which to apply term */ - int timestep; - /** @brief Cartesian position */ - Eigen::Vector3d xyz; - /** @brief Rotation quaternion */ - Eigen::Vector4d wxyz; - /** @brief coefficients for position and rotation */ - Eigen::Vector3d pos_coeffs, rot_coeffs; - /** @brief Link which should reach desired pose */ - std::string link; - /** @brief Static transform applied to the link */ - Eigen::Isometry3d tcp; - - CartPoseTermInfo(); - - /** @brief Used to add term to pci from json */ - // void fromJson(ProblemConstructionInfo& pci, const Json::Value& v) override; - /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; - - static TermInfoPtr create() - { - TermInfoPtr out(new CartPoseTermInfo()); - return out; - } -}; - -/** - \brief Joint space position cost - Position operates on a single point (unlike velocity, etc). This is b/c the primary usecase is joint-space - position waypoints - - \f{align*}{ - \sum_i c_i (x_i - xtarg_i)^2 - \f} - where \f$i\f$ indexes over dof and \f$c_i\f$ are coeffs - */ -struct JointPoseTermInfo : public TermInfo -{ - /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec coeffs; - /** @brief Vector of position targets. This is a required value. Size should be the DOF of the system */ - trajopt::DblVec targets; - /** @brief Vector of position upper limits. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec upper_tols; - /** @brief Vector of position lower limits. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec lower_tols; - /** @brief First time step to which the term is applied. Default: 0 */ - int first_step = 0; - /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ - int last_step = -1; - - /** @brief Initialize term with it's supported types */ - JointPoseTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) - { - } - - /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; - - static TermInfoPtr create() - { - TermInfoPtr out(new JointPoseTermInfo()); - return out; - } -}; - -struct JointVelTermInfo : public TermInfo -{ - /** @brief Vector of coefficients that scale the cost. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec coeffs; - /** @brief Vector of velocity targets. This is a required value. Size should be the DOF of the system */ - trajopt::DblVec targets; - /** @brief Vector of velocity upper limits. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec upper_tols; - /** @brief Vector of velocity lower limits. Size should be the DOF of the system. Default: vector of 0's*/ - trajopt::DblVec lower_tols; - /** @brief First time step to which the term is applied. Default: 0*/ - int first_step = 0; - /** @brief Last time step to which the term is applied. Default: prob.GetNumSteps() - 1*/ - int last_step = -1; - - /** @brief Initialize term with it's supported types */ - JointVelTermInfo() : TermInfo(TT_COST | TT_CNT | TT_USE_TIME) - { - } - - /** @brief Converts term info into cost/constraint and adds it to trajopt problem */ - void addObjectiveTerms(TrajOptProblem& prob) override; - - static TermInfoPtr create() - { - TermInfoPtr out(new JointVelTermInfo()); - return out; - } -}; - -void generateInitialTrajectory(const ProblemInfo& pci, const std::vector& current_joint_values, - trajopt::TrajArray& init_traj); - -} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD b/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD deleted file mode 100644 index 74432fa83c..0000000000 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_interface.h~HEAD +++ /dev/null @@ -1,77 +0,0 @@ -/********************************************************************* - * Software License Agreement (BSD License) - * - * Copyright (c) 2019, PickNik, LLC. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of PickNik nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - *********************************************************************/ - -/* Author: Omid Heidari */ -#pragma once - -#include -#include -#include -#include "problem_description.h" - -namespace trajopt_interface -{ -MOVEIT_CLASS_FORWARD(TrajOptInterface); - -class TrajOptInterface -{ -public: - TrajOptInterface(const ros::NodeHandle& nh = ros::NodeHandle("~")); - - const sco::BasicTrustRegionSQPParameters& getParams() const - { - return params_; - } - - bool solve(const planning_scene::PlanningSceneConstPtr& planning_scene, - const planning_interface::MotionPlanRequest& req, moveit_msgs::MotionPlanDetailedResponse& res); - -protected: - /** @brief Configure everything using the param server */ - void setTrajOptParams(sco::BasicTrustRegionSQPParameters& param); - void setDefaultTrajOPtParams(); - void setProblemInfoParam(ProblemInfo& problem_info); - void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); - trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, - const std::vector& group_joint_names); - - ros::NodeHandle nh_; /// The ROS node handle - sco::BasicTrustRegionSQPParameters params_; - std::vector optimizer_callbacks_; - TrajOptProblemPtr trajopt_problem_; - std::string name_; -}; - -void callBackFunc(sco::OptProb* opt_prob, sco::OptResults& opt_res); -} diff --git a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD b/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD deleted file mode 100644 index 12676f57e7..0000000000 --- a/moveit_planners/trajopt/include/trajopt_interface/trajopt_planning_context.h~HEAD +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once - -#include - -#include -#include - -namespace trajopt_interface -{ -MOVEIT_CLASS_FORWARD(TrajOptPlanningContext); - -class TrajOptPlanningContext : public planning_interface::PlanningContext -{ -public: - TrajOptPlanningContext(const std::string& name, const std::string& group, - const robot_model::RobotModelConstPtr& model); - ~TrajOptPlanningContext() override - { - } - - bool solve(planning_interface::MotionPlanResponse& res) override; - bool solve(planning_interface::MotionPlanDetailedResponse& res) override; - - bool terminate() override; - void clear() override; - -private: - moveit::core::RobotModelConstPtr robot_model_; - - TrajOptInterfacePtr trajopt_interface_; -}; -} // namespace trajopt_interface diff --git a/moveit_planners/trajopt/trajopt/CMakeLists.txt b/moveit_planners/trajopt/trajopt/CMakeLists.txt new file mode 100644 index 0000000000..3e6b065bc2 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/CMakeLists.txt @@ -0,0 +1,70 @@ +cmake_minimum_required(VERSION 2.8.3) +project(trajopt) + +add_compile_options(-std=c++11 -Wall -Wextra) + +find_package(catkin REQUIRED COMPONENTS + trajopt_sco + trajopt_utils + roscpp +) + +find_package(Eigen3 REQUIRED) +find_package(Boost COMPONENTS system python thread program_options REQUIRED) + +find_package(PkgConfig REQUIRED) +pkg_check_modules(JSONCPP jsoncpp) + +link_directories( + /usr/local/lib + /usr/local/lib64 +) + +set(TRAJOPT_SOURCE_FILES + src/trajectory_costs.cpp + src/kinematic_terms.cpp + src/problem_description.cpp + src/utils.cpp +) + +catkin_package( + INCLUDE_DIRS + include + ${EIGEN3_INCLUDE_DIRS} + LIBRARIES + ${PROJECT_NAME} + ${JSONCPP_LIBRARIES} + CATKIN_DEPENDS + trajopt_sco + trajopt_utils + roscpp + DEPENDS + EIGEN3 + Boost +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + SYSTEM ${EIGEN3_INCLUDE_DIRS} + SYSTEM ${Boost_INCLUDE_DIRS} + SYSTEM ${JSONCPP_INCLUDE_DIRS} +) + +add_library(${PROJECT_NAME} ${TRAJOPT_SOURCE_FILES}) +target_link_libraries(${PROJECT_NAME} ${Boost_SYSTEM_LIBRARY} ${JSONCPP_LIBRARIES} ${catkin_LIBRARIES}) +target_compile_options(${PROJECT_NAME} PRIVATE -Wsuggest-override -Wconversion -Wsign-conversion) + +# Mark executables and/or libraries for installation +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +# Mark cpp header files for installation +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp" PATTERN "*.hxx" + PATTERN ".svn" EXCLUDE + ) diff --git a/moveit_planners/trajopt/trajopt/LICENSE b/moveit_planners/trajopt/trajopt/LICENSE new file mode 100644 index 0000000000..9103917b0f --- /dev/null +++ b/moveit_planners/trajopt/trajopt/LICENSE @@ -0,0 +1,11 @@ +Copyright (c) 2013, John Schulman +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. +* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +http://opensource.org/licenses/BSD-2-Clause \ No newline at end of file diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/cache.hxx b/moveit_planners/trajopt/trajopt/include/trajopt/cache.hxx new file mode 100644 index 0000000000..7fc8edaa1c --- /dev/null +++ b/moveit_planners/trajopt/trajopt/include/trajopt/cache.hxx @@ -0,0 +1,26 @@ +#pragma once + +template +class Cache +{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + KeyT keybuf[bufsize]; // circular buffer + ValueT valbuf[bufsize]; // circular buffer + int m_i; + Cache() : m_i(0) { memset(keybuf, 666, sizeof(keybuf)); } + void put(const KeyT& key, const ValueT& value) + { + keybuf[m_i] = key; + valbuf[m_i] = value; + ++m_i; + if (m_i == bufsize) + m_i = 0; + } + ValueT* get(const KeyT& key) + { + KeyT* it = std::find(&keybuf[0], &keybuf[0] + bufsize, key); + return (it == &keybuf[0] + bufsize) ? nullptr : &valbuf[it - &keybuf[0]]; + } +}; diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/common.hpp b/moveit_planners/trajopt/trajopt/include/trajopt/common.hpp new file mode 100644 index 0000000000..41b82a6046 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/include/trajopt/common.hpp @@ -0,0 +1,3 @@ +#pragma once +#include +#include diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h b/moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h index 96274cf9c7..8149180af3 100644 --- a/moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h +++ b/moveit_planners/trajopt/trajopt/include/trajopt/kinematic_terms.h @@ -4,7 +4,7 @@ #include -namespace trajopt_interface +namespace trajopt { /** * @brief Extracts the vector part of quaternion @@ -90,4 +90,4 @@ struct JointVelJacobianCalculator : sco::MatrixOfVector Eigen::MatrixXd operator()(const Eigen::VectorXd& var_vals) const; }; -} // namespace trajopt_interface +} // namespace trajopt diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h b/moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h index 825c82262d..6d6ff865f8 100644 --- a/moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h +++ b/moveit_planners/trajopt/trajopt/include/trajopt/problem_description.h @@ -1,6 +1,6 @@ #pragma once + #include -#include #include #include @@ -8,7 +8,7 @@ #include -namespace trajopt_interface +namespace trajopt { /** @brief Used to apply cost/constraint to joint-space velocity @@ -109,12 +109,12 @@ struct InitInfo }; /** @brief Specifies the type of initialization to use */ Type type; + /** @brief Data used during initialization. Use depends on the initialization selected. This data will be used to create initialization matrix. We need to give the goal information to this init info */ trajopt::TrajArray data; - // Eigen::VectorXd data_vec; - // trajopt::TrajArray data_trajectory; + /** @brief Default value the final column of the optimization is initialized too if time is being used */ double dt = 1.0; }; diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/trajectory_costs.hpp b/moveit_planners/trajopt/trajopt/include/trajopt/trajectory_costs.hpp new file mode 100644 index 0000000000..5741151f74 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/include/trajopt/trajectory_costs.hpp @@ -0,0 +1,533 @@ +#pragma once + +/** +Simple quadratic costs on trajectory +*/ + +#include +#include + +#include "trajopt/common.hpp" + +namespace trajopt +{ +class TRAJOPT_API JointPosEqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointPosEqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the cost as an expression */ + sco::QuadExpr expr_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +/** + * @brief The JointVelIneqCost class + * Assumes that the target is ... + */ +class TRAJOPT_API JointPosIneqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointPosIneqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointPosEqConstraint : public sco::EqConstraint +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointPosEqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targetss, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps */ + std::vector expr_vec_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointPosIneqConstraint : public sco::IneqConstraint +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointPosIneqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointVelEqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointVelEqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values using Eigen*/ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the cost as an expression */ + sco::QuadExpr expr_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointVelIneqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointVelIneqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*num_timesteps*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointVelEqConstraint : public sco::EqConstraint +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointVelEqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-1) */ + std::vector expr_vec_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointVelIneqConstraint : public sco::IneqConstraint +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointVelIneqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-1)*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointAccEqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointAccEqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the cost as an expression */ + sco::QuadExpr expr_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointAccIneqCost : public sco::Cost +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointAccIneqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of acceleration targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-2)*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointAccEqConstraint : public sco::EqConstraint +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointAccEqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-2) */ + std::vector expr_vec_; + /** @brief Vector of acceleration targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointAccIneqConstraint : public sco::IneqConstraint +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointAccIneqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of acceleration targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-2)*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointJerkEqCost : public sco::Cost +{ +public: + /** @brief Forms error in QuadExpr - independent of penalty type */ + JointJerkEqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the cost as an expression */ + sco::QuadExpr expr_; + /** @brief Vector of jerk targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointJerkIneqCost : public sco::Cost +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointJerkIneqCost(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexObjectivePtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + double value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of jerk targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-4)*2 */ + std::vector expr_vec_; +}; + +class TRAJOPT_API JointJerkEqConstraint : public sco::EqConstraint +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointJerkEqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-4) */ + std::vector expr_vec_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; +}; + +class TRAJOPT_API JointJerkIneqConstraint : public sco::IneqConstraint +{ +public: + /** @brief Forms error in a vector of AffExpr - independent of penalty type */ + JointJerkIneqConstraint(const VarArray& traj, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_limits, + const Eigen::VectorXd& lower_limits, + int& first_step, + int& last_step); + /** @brief Convexifies cost expression - In this case, it is already quadratic so there's nothing to do */ + sco::ConvexConstraintsPtr convex(const DblVec& x, sco::Model* model) override; + /** @brief Numerically evaluate cost given the vector of values */ + DblVec value(const DblVec&) override; + sco::VarVector getVars() override { return vars_.flatten(); } +private: + /** @brief The variables being optimized. Used to properly index the vector being optimized */ + VarArray vars_; + /** @brief The coefficients used to weight the cost */ + Eigen::VectorXd coeffs_; + /** @brief Vector of upper tolerances */ + Eigen::VectorXd upper_tols_; + /** @brief Vector of lower tolerances */ + Eigen::VectorXd lower_tols_; + /** @brief Vector of velocity targets */ + Eigen::VectorXd targets_; + /** @brief First time step to which the term is applied */ + int first_step_; + /** @brief Last time step to which the term is applied */ + int last_step_; + /** @brief Stores the costs as an expression. Will be length num_jnts*(num_timesteps-4)*2 */ + std::vector expr_vec_; +}; +} // namespace trajopt diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/typedefs.hpp b/moveit_planners/trajopt/trajopt/include/trajopt/typedefs.hpp new file mode 100644 index 0000000000..28b06f3054 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/include/trajopt/typedefs.hpp @@ -0,0 +1,77 @@ +#pragma once +#include +#include +TRAJOPT_IGNORE_WARNINGS_PUSH +#include +#include +#include +TRAJOPT_IGNORE_WARNINGS_POP + +#include +#include + +namespace trajopt +{ +typedef util::BasicArray VarArray; +typedef util::BasicArray AffArray; +typedef util::BasicArray CntArray; +typedef Eigen::Matrix DblMatrix; +typedef Eigen::Matrix TrajArray; +typedef sco::DblVec DblVec; +typedef sco::IntVec IntVec; + + +/** @brief Adds plotting to the CostFromErrFunc class in trajopt_sco */ +class TrajOptCostFromErrFunc : public sco::CostFromErrFunc +{ +public: + /// supply error function, obtain derivative numerically + TrajOptCostFromErrFunc(sco::VectorOfVectorPtr f, + const sco::VarVector& vars, + const Eigen::VectorXd& coeffs, + sco::PenaltyType pen_type, + const std::string& name) + : CostFromErrFunc(f, vars, coeffs, pen_type, name) + { + } + + /// supply error function and gradient + TrajOptCostFromErrFunc(sco::VectorOfVectorPtr f, + sco::MatrixOfVectorPtr dfdx, + const sco::VarVector& vars, + const Eigen::VectorXd& coeffs, + sco::PenaltyType pen_type, + const std::string& name) + : CostFromErrFunc(f, dfdx, vars, coeffs, pen_type, name) + { + } + +}; + +/** @brief Adds plotting to the ConstraintFromFunc class in trajopt_sco */ +class TrajOptConstraintFromErrFunc : public sco::ConstraintFromErrFunc +{ +public: + /// supply error function, obtain derivative numerically + TrajOptConstraintFromErrFunc(sco::VectorOfVectorPtr f, + const sco::VarVector& vars, + const Eigen::VectorXd& coeffs, + sco::ConstraintType type, + const std::string& name) + : ConstraintFromErrFunc(f, vars, coeffs, type, name) + { + } + + /// supply error function and gradient + TrajOptConstraintFromErrFunc(sco::VectorOfVectorPtr f, + sco::MatrixOfVectorPtr dfdx, + const sco::VarVector& vars, + const Eigen::VectorXd& coeffs, + sco::ConstraintType type, + const std::string& name) + : ConstraintFromErrFunc(f, dfdx, vars, coeffs, type, name) + { + } + +}; +} diff --git a/moveit_planners/trajopt/trajopt/include/trajopt/utils.hpp b/moveit_planners/trajopt/trajopt/include/trajopt/utils.hpp new file mode 100644 index 0000000000..9d24300402 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/include/trajopt/utils.hpp @@ -0,0 +1,153 @@ +#pragma once +#include +TRAJOPT_IGNORE_WARNINGS_PUSH +#include +TRAJOPT_IGNORE_WARNINGS_POP + +#include + +namespace trajopt +{ +template +using AlignedUnorderedMap = std::unordered_map, + std::equal_to, + Eigen::aligned_allocator>>; + +/** +Extract trajectory array from solution vector x using indices in array vars +*/ +TrajArray TRAJOPT_API getTraj(const DblVec& x, const VarArray& vars); +TrajArray TRAJOPT_API getTraj(const DblVec& x, const AffArray& arr); + +inline DblVec trajToDblVec(const TrajArray& x) { return DblVec(x.data(), x.data() + x.rows() * x.cols()); } + +/** + * @brief Appends b to a of type VectorXd + */ +inline Eigen::VectorXd concat(const Eigen::VectorXd& a, const Eigen::VectorXd& b) +{ + Eigen::VectorXd out(a.size() + b.size()); + out.topRows(a.size()) = a; + out.middleRows(a.size(), b.size()) = b; + return out; +} + +/** + * @brief Appends b to a of type T + */ +template +std::vector concat(const std::vector& a, const std::vector& b) +{ + std::vector out; + std::vector x(a.size() + b.size()); + out.insert(out.end(), a.begin(), a.end()); + out.insert(out.end(), b.begin(), b.end()); + return out; +} + +template +std::vector singleton(const T& x) +{ + return std::vector(1, x); +} + +void TRAJOPT_API AddVarArrays(sco::OptProb& prob, + int rows, + const std::vector& cols, + const std::vector& name_prefix, + const std::vector& newvars); + +void TRAJOPT_API AddVarArray(sco::OptProb& prob, int rows, int cols, const std::string& name_prefix, VarArray& newvars); + +/** @brief Store Safety Margin Data for a given timestep */ +struct SafetyMarginData +{ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + SafetyMarginData(const double& default_safety_margin, const double& default_safety_margin_coeff) + : default_safety_margin_data_(default_safety_margin, default_safety_margin_coeff) + , max_safety_margin_(default_safety_margin) + { + } + + /** + * @brief Set the safety margin for a given contact pair + * + * The order of the object names does not matter, that is handled internal to + * the class. + * + * @param obj1 The first object name + * @param obj2 The Second object name + * @param safety_margins contacts with distance < safety_margin are penalized + * @param safety_margin_coeffs A safety margin coefficient vector where each + * element corresponds to a given timestep. + */ + void SetPairSafetyMarginData(const std::string& obj1, + const std::string& obj2, + const double& safety_margin, + const double& safety_margin_coeff) + { + Eigen::Vector2d data(safety_margin, safety_margin_coeff); + + pair_lookup_table_[obj1 + obj2] = data; + pair_lookup_table_[obj2 + obj1] = data; + + if (safety_margin > max_safety_margin_) + { + max_safety_margin_ = safety_margin; + } + } + + const Eigen::Vector2d& getPairSafetyMarginData(const std::string& obj1, const std::string& obj2) const + { + const std::string& key = obj1 + obj2; + auto it = pair_lookup_table_.find(key); + + if (it != pair_lookup_table_.end()) + { + return it->second; + } + else + { + return default_safety_margin_data_; + } + } + + const double& getMaxSafetyMargin() const { return max_safety_margin_; } +private: + /// The coeff used during optimization + /// safety margin: contacts with distance < dist_pen are penalized + /// Stores [dist_pen, coeff] + Eigen::Vector2d default_safety_margin_data_; + + /// This use when requesting collision data because you can only provide a + /// single contact distance threshold. + double max_safety_margin_; + + /// A map of link pair to contact distance setting [dist_pen, coeff] + AlignedUnorderedMap pair_lookup_table_; +}; +typedef std::shared_ptr SafetyMarginDataPtr; +typedef std::shared_ptr SafetyMarginDataConstPtr; + +/** + * @brief This is a utility function for creating the Safety Margin data vector + * @param num_elements The number of objects to create + * @param default_safety_margin Default safety margin + * @param default_safety_margin_coeff Default safety margin coeff + * @return A vector of Safety Margin Data + */ +inline std::vector createSafetyMarginDataVector(int num_elements, + const double& default_safety_margin, + const double& default_safety_margin_coeff) +{ + std::vector info; + info.reserve(static_cast(num_elements)); + for (auto i = 0; i < num_elements; ++i) + { + info.push_back(SafetyMarginDataPtr(new SafetyMarginData(default_safety_margin, default_safety_margin_coeff))); + } + return info; +} +} diff --git a/moveit_planners/trajopt/trajopt/package.xml b/moveit_planners/trajopt/trajopt/package.xml new file mode 100644 index 0000000000..d17422a2a7 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/package.xml @@ -0,0 +1,28 @@ + + + trajopt + 0.1.0 + The trajopt package + Levi Armstrong + BSD + Apache 2.0 + Levi Armstrong + John Schulman + + catkin + trajopt_sco + trajopt_utils + roscpp + + gtest + rostest + roslib + trajopt_test_support + libpcl-all-dev + pcl_conversions + pr2_description + + + + + diff --git a/moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp b/moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp index 92d75fb78b..4559e5b8a1 100644 --- a/moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp +++ b/moveit_planners/trajopt/trajopt/src/kinematic_terms.cpp @@ -4,13 +4,13 @@ #include #include -#include "trajopt_interface/kinematic_terms.h" +#include "trajopt/kinematic_terms.h" using namespace std; using namespace sco; using namespace Eigen; -namespace trajopt_interface +namespace trajopt { VectorXd CartPoseErrCalculator::operator()(const VectorXd& dof_vals) const { @@ -61,4 +61,4 @@ MatrixXd JointVelJacobianCalculator::operator()(const VectorXd& var_vals) const return jac; } -} // namespace trajopt_interface +} // namespace trajopt diff --git a/moveit_planners/trajopt/trajopt/src/problem_description.cpp b/moveit_planners/trajopt/trajopt/src/problem_description.cpp index 7cd678282c..3a7c9477ca 100644 --- a/moveit_planners/trajopt/trajopt/src/problem_description.cpp +++ b/moveit_planners/trajopt/trajopt/src/problem_description.cpp @@ -32,6 +32,7 @@ *********************************************************************/ #include +#include #include @@ -39,7 +40,6 @@ #include #include -#include #include #include #include @@ -47,8 +47,9 @@ #include #include -#include "trajopt_interface/problem_description.h" -#include "trajopt_interface/kinematic_terms.h" +#include +#include +#include "trajopt/problem_description.h" /** * @brief Checks the size of the parameter given and throws if incorrect @@ -71,7 +72,7 @@ void checkParameterSize(trajopt::DblVec& parameter, const unsigned int& expected } } -namespace trajopt_interface +namespace trajopt { TrajOptProblem::TrajOptProblem() { diff --git a/moveit_planners/trajopt/trajopt/src/trajectory_costs.cpp b/moveit_planners/trajopt/trajopt/src/trajectory_costs.cpp new file mode 100644 index 0000000000..eaaa1b0fd4 --- /dev/null +++ b/moveit_planners/trajopt/trajopt/src/trajectory_costs.cpp @@ -0,0 +1,955 @@ +#include +TRAJOPT_IGNORE_WARNINGS_PUSH +#include +TRAJOPT_IGNORE_WARNINGS_POP + +#include +#include +#include + +#include "trajopt/trajectory_costs.hpp" + +namespace +{ +/** @brief Returns the difference between each row of a matrixXd and the row before */ +static Eigen::MatrixXd diffAxis0(const Eigen::MatrixXd& in) +{ + return in.middleRows(1, in.rows() - 1) - in.middleRows(0, in.rows() - 1); +} +} // namespace + +namespace trajopt +{ +//////////// Joint cost functions ///////////////// + +//////////////////// Position ///////////////////// +JointPosEqCost::JointPosEqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : Cost("JointPosEq"), vars_(vars), coeffs_(coeffs), targets_(targets), first_step_(first_step), last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // pos = x1 - targ + sco::AffExpr pos; + sco::exprInc(pos, sco::exprMult(vars(i, j), 1)); + sco::exprDec(pos, targets_[j]); + // expr_ = coeff * vel^2 + sco::exprInc(expr_, sco::exprMult(sco::exprSquare(pos), coeffs_[j])); + } + } +} +double JointPosEqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = (getTraj(xvec, vars_)); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())).rowwise() - targets_.transpose(); + // Element-wise square it, multiply it by a diagonal matrix of coefficients, and sums output + return (diff.array().square().matrix() * coeffs_.asDiagonal()).sum(); +} +sco::ConvexObjectivePtr JointPosEqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + out->addQuadExpr(expr_); + return out; +} + +JointPosIneqCost::JointPosIneqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : Cost("JointPosIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr expr; + sco::AffExpr expr_neg; + // pos = x1 - targ + sco::AffExpr pos; + sco::exprInc(pos, sco::exprMult(vars(i, j), 1)); + sco::exprDec(pos, targets_[j]); + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprDec(expr, pos); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprDec(expr_neg, pos); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +double JointPosIneqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd pos = traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()); + // Subtract targets to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (pos.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + return diff1.cwiseMax(0).sum() + diff2.cwiseMax(0).sum(); +} + +sco::ConvexObjectivePtr JointPosIneqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addHinge(expr, 1); + } + return out; +} + +JointPosEqConstraint::JointPosEqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : EqConstraint("JointPosEq") + , vars_(vars) + , coeffs_(coeffs) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // pos = x1 - targ + sco::AffExpr pos; + sco::exprInc(pos, sco::exprMult(vars(i, j), 1)); + sco::exprDec(pos, targets_[j]); + // expr_ = coeff * vel - Not squared b/c QuadExpr cnt not yet supported (TODO) + expr_vec_.push_back(sco::exprMult(pos, coeffs_[j])); + } + } +} + +DblVec JointPosEqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())).rowwise() - targets_.transpose(); + // Squares it, multiplies it by a diagonal matrix of coefficients, and converts to vector + return util::toDblVec((diff.array().square()).matrix() * coeffs_.asDiagonal()); +} +sco::ConvexConstraintsPtr JointPosEqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + for (sco::AffExpr& expr : expr_vec_) + { + out->addEqCnt(expr); + } + return out; +} + +JointPosIneqConstraint::JointPosIneqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : IneqConstraint("JointPosIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr expr; + sco::AffExpr expr_neg; + // pos = x1 - targ + sco::AffExpr pos; + sco::exprInc(pos, sco::exprMult(vars(i, j), 1)); + sco::exprDec(pos, targets_[j]); + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprDec(expr, pos); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form lower limit expr = (upper_tol-(vel-targ)) + sco::exprDec(expr_neg, pos); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +DblVec JointPosIneqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd pos = diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())); + // Subtract targets to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (pos.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + Eigen::MatrixXd out(diff1.rows(), diff1.cols() + diff2.cols()); + out << diff1, diff2; + return util::toDblVec(out); +} + +sco::ConvexConstraintsPtr JointPosIneqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addIneqCnt(expr); + } + return out; +} + +//////////////////// Velocity ///////////////////// +JointVelEqCost::JointVelEqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : Cost("JointVelEq"), vars_(vars), coeffs_(coeffs), targets_(targets), first_step_(first_step), last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 1; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // vel = (x2 - x1) - targ + sco::AffExpr vel; + sco::exprInc(vel, sco::exprMult(vars(i, j), -1)); + sco::exprInc(vel, sco::exprMult(vars(i + 1, j), 1)); + exprDec(vel, targets_[j]); + // expr_ = coeff * vel^2 + exprInc(expr_, exprMult(exprSquare(vel), coeffs_[j])); + } + } +} +double JointVelEqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = (getTraj(xvec, vars_)); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = (diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))).rowwise() - + targets_.transpose(); + // Element-wise square it, multiply it by a diagonal matrix of coefficients, and sums output + return (diff.array().square().matrix() * coeffs_.asDiagonal()).sum(); +} +sco::ConvexObjectivePtr JointVelEqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + out->addQuadExpr(expr_); + return out; +} + +JointVelIneqCost::JointVelIneqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : Cost("JointVelIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 1; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // vel = (x2 - x1) - targ + sco::AffExpr vel; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(vel, sco::exprMult(vars(i, j), -1)); + sco::exprInc(vel, sco::exprMult(vars(i + 1, j), 1)); + sco::exprDec(vel, targets_[j]); // offset to center about 0 + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, vel); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form lower limit expr = (upper_tol-(vel-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, vel); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +double JointVelIneqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd vel = diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (vel.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + return diff1.cwiseMax(0).sum() + diff2.cwiseMax(0).sum(); +} + +sco::ConvexObjectivePtr JointVelIneqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addHinge(expr, 1); + } + return out; +} + +JointVelEqConstraint::JointVelEqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : EqConstraint("JointVelEq") + , vars_(vars) + , coeffs_(coeffs) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 1; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // vel = (x2 - x1) - targ + sco::AffExpr vel; + sco::exprInc(vel, sco::exprMult(vars(i, j), -1)); + sco::exprInc(vel, sco::exprMult(vars(i + 1, j), 1)); + sco::exprDec(vel, targets_[j]); + // expr_ = coeff * vel - Not squared b/c QuadExpr cnt not yet supported (TODO) + expr_vec_.push_back(sco::exprMult(vel, coeffs_[j])); + } + } +} + +DblVec JointVelEqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = (diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))).rowwise() - + targets_.transpose(); + // Squares it, multiplies it by a diagonal matrix of coefficients, and converts to vector + return util::toDblVec((diff.array().square()).matrix() * coeffs_.asDiagonal()); +} +sco::ConvexConstraintsPtr JointVelEqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + for (sco::AffExpr& expr : expr_vec_) + { + out->addEqCnt(expr); + } + return out; +} + +JointVelIneqConstraint::JointVelIneqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : IneqConstraint("JointVelIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 1; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // vel = (x2 - x1) - targ + sco::AffExpr vel; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(vel, sco::exprMult(vars(i, j), -1)); + sco::exprInc(vel, sco::exprMult(vars(i + 1, j), 1)); + sco::exprDec(vel, targets_[j]); // offset to center about 0 + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, vel); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form lower limit expr = (lower_tol-(vel-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, vel); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +DblVec JointVelIneqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd vel = diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (vel.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + Eigen::MatrixXd out(diff1.rows(), diff1.cols() + diff2.cols()); + out << diff1, diff2; + return util::toDblVec(out.cwiseMax(0)); +} + +sco::ConvexConstraintsPtr JointVelIneqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addIneqCnt(expr); + } + return out; +} + +//////////////////// Acceleration ///////////////////// +JointAccEqCost::JointAccEqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : Cost("JointAccEq"), vars_(vars), coeffs_(coeffs), targets_(targets), first_step_(first_step), last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 2; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // acc = (x3 - 2*x2 + x1) - targ + sco::AffExpr acc; + sco::exprInc(acc, sco::exprMult(vars(i, j), 1.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 1, j), -2.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 2, j), 1.0)); + + sco::exprDec(acc, targets_[j]); + // expr_ = coeff * acc^2 + sco::exprInc(expr_, sco::exprMult(sco::exprSquare(acc), coeffs_[j])); + } + } +} +double JointAccEqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = (getTraj(xvec, vars_)); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())))).rowwise() - + targets_.transpose(); + // Element-wise square it, multiply it by a diagonal matrix of coefficients, and sums output + return (diff.array().square().matrix() * coeffs_.asDiagonal()).sum(); +} +sco::ConvexObjectivePtr JointAccEqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + out->addQuadExpr(expr_); + return out; +} + +JointAccIneqCost::JointAccIneqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : Cost("JointAccIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 2; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // acc = (x3 - 2*x2 + x1) - targ + sco::AffExpr acc; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(acc, sco::exprMult(vars(i, j), 1.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 1, j), -2.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 2, j), 1.0)); + sco::exprDec(acc, targets_[j]); // offset to center about 0 + + // Form upper limit expr = - (upper_tol-(acc-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, acc); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form lower limit expr = (lower_tol-(acc-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, acc); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +double JointAccIneqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd acc = diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (acc.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + return diff1.cwiseMax(0).sum() + diff2.cwiseMax(0).sum(); +} + +sco::ConvexObjectivePtr JointAccIneqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addHinge(expr, 1); + } + return out; +} + +JointAccEqConstraint::JointAccEqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : EqConstraint("JointAccEq") + , vars_(vars) + , coeffs_(coeffs) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 2; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // acc = (x3 - 2*x2 + x1) - targ + sco::AffExpr acc; + sco::exprInc(acc, sco::exprMult(vars(i, j), 1.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 1, j), -2.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 2, j), 1.0)); + + sco::exprDec(acc, targets_[j]); // offset to center about 0 + // expr_ = coeff * vel - Not squared b/c QuadExpr cnt not yet supported (TODO) + expr_vec_.push_back(sco::exprMult(acc, coeffs_[j])); + } + } +} + +DblVec JointAccEqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())))).rowwise() - + targets_.transpose(); + // Squares it, multiplies it by a diagonal matrix of coefficients, and converts to vector + return util::toDblVec((diff.array().square()).matrix() * coeffs_.asDiagonal()); +} +sco::ConvexConstraintsPtr JointAccEqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + for (sco::AffExpr& expr : expr_vec_) + { + out->addEqCnt(expr); + } + return out; +} + +JointAccIneqConstraint::JointAccIneqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : IneqConstraint("JointAccIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + // Form upper limit expr = - (upper_tol-(vel-targ)) + for (int i = first_step_; i <= last_step_ - 2; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + // acc = (x3 - 2*x2 + x1) - targ + sco::AffExpr acc; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(acc, sco::exprMult(vars(i, j), 1.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 1, j), -2.0)); + sco::exprInc(acc, sco::exprMult(vars(i + 2, j), 1.0)); + sco::exprDec(acc, targets_[j]); // offset to center about 0 + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, acc); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, acc); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +DblVec JointAccIneqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd acc = diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (acc.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + Eigen::MatrixXd out(diff1.rows(), diff1.cols() + diff2.cols()); + out << diff1, diff2; + return util::toDblVec(out.cwiseMax(0)); +} + +sco::ConvexConstraintsPtr JointAccIneqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addIneqCnt(expr); + } + return out; +} + +//////////////////// Jerk ///////////////////// +JointJerkEqCost::JointJerkEqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : Cost("JointJerkEq"), vars_(vars), coeffs_(coeffs), targets_(targets), first_step_(first_step), last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 4; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr jerk; + sco::exprInc(jerk, sco::exprMult(vars(i, j), -1.0 / 2.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 1, j), 1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 2, j), 0.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 3, j), -1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 4, j), 1.0 / 2.0)); + + sco::exprDec(jerk, targets_[j]); + // expr_ = coeff * jerk^2 + sco::exprInc(expr_, sco::exprMult(sco::exprSquare(jerk), coeffs_[j])); + } + } +} +double JointJerkEqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = (getTraj(xvec, vars_)); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (diffAxis0(diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))))) + .rowwise() - + targets_.transpose(); + // Element-wise square it, multiply it by a diagonal matrix of coefficients, and sums output + return (diff.array().square().matrix() * coeffs_.asDiagonal()).sum(); +} +sco::ConvexObjectivePtr JointJerkEqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + out->addQuadExpr(expr_); + return out; +} + +JointJerkIneqCost::JointJerkIneqCost(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : Cost("JointJerkIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 4; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr jerk; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(jerk, sco::exprMult(vars(i, j), -1.0 / 2.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 1, j), 1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 2, j), 0.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 3, j), -1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 4, j), 1.0 / 2.0)); + sco::exprDec(jerk, targets_[j]); + + // Form upper limit expr = - (upper_tol-(jerk-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, jerk); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form lower limit expr = (lower_tol-(acc-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, jerk); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +double JointJerkIneqCost::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd jerk = + diffAxis0(diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols())))); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (jerk.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + return diff1.cwiseMax(0).sum() + diff2.cwiseMax(0).sum(); +} + +sco::ConvexObjectivePtr JointJerkIneqCost::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexObjectivePtr out(new sco::ConvexObjective(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addHinge(expr, 1); + } + return out; +} + +JointJerkEqConstraint::JointJerkEqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + int& first_step, + int& last_step) + : EqConstraint("JointJerkEq") + , vars_(vars) + , coeffs_(coeffs) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 4; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr jerk; + sco::exprInc(jerk, sco::exprMult(vars(i, j), -1.0 / 2.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 1, j), 1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 2, j), 0.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 3, j), -1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 4, j), 1.0 / 2.0)); + + sco::exprDec(jerk, targets_[j]); // offset to center about 0 + // expr_ = coeff * jerk - Not squared b/c QuadExpr cnt not yet supported (TODO) + expr_vec_.push_back(sco::exprMult(jerk, coeffs_[j])); + } + } +} + +DblVec JointJerkEqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows and subtract each row by the targets_ vector + Eigen::MatrixXd diff = + (diffAxis0(diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))))) + .rowwise() - + targets_.transpose(); + // Squares it, multiplies it by a diagonal matrix of coefficients, and converts to vector + return util::toDblVec((diff.array().square()).matrix() * coeffs_.asDiagonal()); +} +sco::ConvexConstraintsPtr JointJerkEqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + for (sco::AffExpr& expr : expr_vec_) + { + out->addEqCnt(expr); + } + return out; +} + +JointJerkIneqConstraint::JointJerkIneqConstraint(const VarArray& vars, + const Eigen::VectorXd& coeffs, + const Eigen::VectorXd& targets, + const Eigen::VectorXd& upper_tols, + const Eigen::VectorXd& lower_tols, + int& first_step, + int& last_step) + : IneqConstraint("JointJerkIneq") + , vars_(vars) + , coeffs_(coeffs) + , upper_tols_(upper_tols) + , lower_tols_(lower_tols) + , targets_(targets) + , first_step_(first_step) + , last_step_(last_step) +{ + for (int i = first_step_; i <= last_step_ - 4; ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + sco::AffExpr jerk; + sco::AffExpr expr; + sco::AffExpr expr_neg; + sco::exprInc(jerk, sco::exprMult(vars(i, j), -1.0 / 2.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 1, j), 1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 2, j), 0.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 3, j), -1.0)); + sco::exprInc(jerk, sco::exprMult(vars(i + 4, j), 1.0 / 2.0)); + sco::exprDec(jerk, targets_[j]); // offset to center about 0 + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr, upper_tols_[j]); // expr_ = upper_tol + sco::exprDec(expr, jerk); // expr = upper_tol_- (vel - targets_) + sco::exprScale(expr, -coeffs[j]); // expr = - (upper_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr); + + // Form upper limit expr = - (upper_tol-(vel-targ)) + sco::exprInc(expr_neg, lower_tols_[j]); // expr_ = lower_tol_ + sco::exprDec(expr_neg, jerk); // expr = lower_tol_- (vel - targets_) + sco::exprScale(expr_neg, coeffs[j]); // expr = (lower_tol_- (vel - targets_)) * coeffs_ + expr_vec_.push_back(expr_neg); + } + } +} + +DblVec JointJerkIneqConstraint::value(const DblVec& xvec) +{ + // Convert vector from optimization to trajectory + Eigen::MatrixXd traj = getTraj(xvec, vars_); + // Takes diff b/n the subsequent rows to get velocity + Eigen::MatrixXd acc = diffAxis0(diffAxis0(traj.block(first_step_, 0, last_step_ - first_step_ + 1, traj.cols()))); + // Subtract targets_ to center about 0 and then subtract from tolerance + Eigen::MatrixXd diff0 = (acc.rowwise() - targets_.transpose()); + Eigen::MatrixXd diff1 = (diff0.rowwise() - upper_tols_.transpose()) * coeffs_.asDiagonal(); + Eigen::MatrixXd diff2 = ((diff0 * -1).rowwise() + lower_tols_.transpose()) * coeffs_.asDiagonal(); + // Applies hinge, multiplies it by a diagonal matrix of coefficients, sums each corresponding value, and converts to + // vector + Eigen::MatrixXd out(diff1.rows(), diff1.cols() + diff2.cols()); + out << diff1, diff2; + return util::toDblVec(out.cwiseMax(0)); +} + +sco::ConvexConstraintsPtr JointJerkIneqConstraint::convex(const DblVec& /*x*/, sco::Model* model) +{ + sco::ConvexConstraintsPtr out(new sco::ConvexConstraints(model)); + // Add hinge cost. Set the coefficient to 1 here since we include it in the AffExpr already + // This is necessary since we want a seperate coefficient per joint + for (sco::AffExpr& expr : expr_vec_) + { + out->addIneqCnt(expr); + } + return out; +} + +} // namespace trajopt diff --git a/moveit_planners/trajopt/trajopt/src/utils.cpp b/moveit_planners/trajopt/trajopt/src/utils.cpp new file mode 100644 index 0000000000..95fb423fbb --- /dev/null +++ b/moveit_planners/trajopt/trajopt/src/utils.cpp @@ -0,0 +1,90 @@ +#include +TRAJOPT_IGNORE_WARNINGS_PUSH +#include +#include +TRAJOPT_IGNORE_WARNINGS_POP + +#include +#include + +namespace trajopt +{ +TrajArray getTraj(const DblVec& x, const VarArray& vars) +{ + TrajArray out(vars.rows(), vars.cols()); + for (int i = 0; i < vars.rows(); ++i) + { + for (int j = 0; j < vars.cols(); ++j) + { + out(i, j) = vars(i, j).value(x); + } + } + return out; +} + +TrajArray getTraj(const DblVec& x, const AffArray& arr) +{ + Eigen::MatrixXd out(arr.rows(), arr.cols()); + for (int i = 0; i < arr.rows(); ++i) + { + for (int j = 0; j < arr.cols(); ++j) + { + out(i, j) = arr(i, j).value(x); + } + } + return out; +} + +void AddVarArrays(sco::OptProb& prob, + int rows, + const IntVec& cols, + const std::vector& name_prefix, + const std::vector& newvars) +{ + size_t n_arr = name_prefix.size(); + assert(static_cast(n_arr) == newvars.size()); + + std::vector index(n_arr); + for (size_t i = 0; i < n_arr; ++i) + { + newvars[i]->resize(rows, cols[i]); + index[i].resize(rows, cols[i]); + } + + std::vector names; + int var_idx = prob.getNumVars(); + for (int i = 0; i < rows; ++i) + { + for (size_t k = 0; k < n_arr; ++k) + { + for (int j = 0; j < cols[k]; ++j) + { + index[k](i, j) = var_idx; + names.push_back((boost::format("%s_%i_%i") % name_prefix[k] % i % j).str()); + ++var_idx; + } + } + } + prob.createVariables(names); // note that w,r, are both unbounded + + const std::vector& vars = prob.getVars(); + for (size_t k = 0; k < n_arr; ++k) + { + for (int i = 0; i < rows; ++i) + { + for (int j = 0; j < cols[k]; ++j) + { + (*newvars[k])(i, j) = vars[static_cast(index[k](i, j))]; + } + } + } +} + +void AddVarArray(sco::OptProb& prob, int rows, int cols, const std::string& name_prefix, VarArray& newvars) +{ + std::vector arrs(1, &newvars); + std::vector prefixes(1, name_prefix); + std::vector colss(1, cols); + AddVarArrays(prob, rows, colss, prefixes, arrs); +} +} diff --git a/moveit_planners/trajopt/trajopt_interface/CMakeLists.txt b/moveit_planners/trajopt/trajopt_interface/CMakeLists.txt index 344c2b0c31..5627a8949d 100644 --- a/moveit_planners/trajopt/trajopt_interface/CMakeLists.txt +++ b/moveit_planners/trajopt/trajopt_interface/CMakeLists.txt @@ -7,7 +7,6 @@ if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) set(CMAKE_BUILD_TYPE Release) endif() -<<<<<<< HEAD find_package(catkin REQUIRED COMPONENTS moveit_core @@ -16,8 +15,9 @@ find_package(catkin REQUIRED moveit_ros_planning_interface pluginlib roscpp - rosparam_shortcuts trajopt + trajopt_sco + trajopt_utils ) catkin_package( @@ -46,8 +46,6 @@ include_directories( add_library( ${PROJECT_NAME} src/trajopt_interface.cpp - src/problem_description.cpp - src/kinematic_terms.cpp src/trajopt_planning_context.cpp ) @@ -63,28 +61,11 @@ set_target_properties( VERSION "${${PROJECT_NAME}_VERSION}" ) -======= -find_package(catkin REQUIRED COMPONENTS - moveit_core - roscpp - pluginlib -) - -catkin_package( - CATKIN_DEPENDS - moveit_core -) - -# The following include_directory should have include folder of the new planner. -include_directories(${Boost_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} - ${TrajOpt_INCLUDE_DIRS}) ->>>>>>> TrajOpt Planner (Empty Template) (#1478) # TrajOpt planning plugin add_library(moveit_trajopt_planner_plugin src/trajopt_planner_manager.cpp) set_target_properties(moveit_trajopt_planner_plugin PROPERTIES VERSION "${${PROJECT_NAME}_VERSION}") -<<<<<<< HEAD + target_link_libraries(moveit_trajopt_planner_plugin ${PROJECT_NAME} ${catkin_LIBRARIES}) ############# @@ -129,14 +110,4 @@ if(CATKIN_ENABLE_TESTING) ${PROJECT_NAME} ) -endif() -======= - -install(TARGETS - moveit_trajopt_planner_plugin - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) - -install(FILES trajopt_interface_plugin_description.xml - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ->>>>>>> TrajOpt Planner (Empty Template) (#1478) +endif() \ No newline at end of file diff --git a/moveit_planners/trajopt/trajopt_interface/README.md b/moveit_planners/trajopt/trajopt_interface/README.md index 98824eadb2..84e0ce1d44 100644 --- a/moveit_planners/trajopt/trajopt_interface/README.md +++ b/moveit_planners/trajopt/trajopt_interface/README.md @@ -1 +1 @@ -As of August 2019, this is a work in progress towards adding trajopt motion planning algorithm to MoveIt as a planner plugin. \ No newline at end of file +As of August 2019, this is a work in progress towards adding trajopt motion planning algorithm to MoveIt as a planner plugin. diff --git a/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h index 74432fa83c..ba1a2dd5c3 100644 --- a/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h +++ b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_interface.h @@ -36,9 +36,11 @@ #pragma once #include -#include + #include -#include "problem_description.h" + +#include +#include namespace trajopt_interface { @@ -61,15 +63,15 @@ class TrajOptInterface /** @brief Configure everything using the param server */ void setTrajOptParams(sco::BasicTrustRegionSQPParameters& param); void setDefaultTrajOPtParams(); - void setProblemInfoParam(ProblemInfo& problem_info); - void setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name); + void setProblemInfoParam(trajopt::ProblemInfo& problem_info); + void setJointPoseTermInfoParams(trajopt::JointPoseTermInfoPtr& jp, std::string name); trajopt::DblVec extractStartJointValues(const planning_interface::MotionPlanRequest& req, const std::vector& group_joint_names); ros::NodeHandle nh_; /// The ROS node handle sco::BasicTrustRegionSQPParameters params_; std::vector optimizer_callbacks_; - TrajOptProblemPtr trajopt_problem_; + trajopt::TrajOptProblemPtr trajopt_problem_; std::string name_; }; diff --git a/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h index 12676f57e7..9c3d6601e4 100644 --- a/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h +++ b/moveit_planners/trajopt/trajopt_interface/include/trajopt_interface/trajopt_planning_context.h @@ -2,7 +2,7 @@ #include -#include +#include #include namespace trajopt_interface diff --git a/moveit_planners/trajopt/trajopt_interface/package.xml b/moveit_planners/trajopt/trajopt_interface/package.xml index 050d71b5d4..d12e387533 100644 --- a/moveit_planners/trajopt/trajopt_interface/package.xml +++ b/moveit_planners/trajopt/trajopt_interface/package.xml @@ -1,6 +1,7 @@ moveit_planners_trajopt 1.0.1 + TrajOpt planning plugin, an optimization based motion planner Omid Heidari diff --git a/moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp b/moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp index 4f76c1add2..1fa526b385 100644 --- a/moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp +++ b/moveit_planners/trajopt/trajopt_interface/src/trajopt_interface.cpp @@ -42,11 +42,10 @@ #include #include #include - +#include #include #include -#include #include #include @@ -54,13 +53,12 @@ #include #include "trajopt_interface/trajopt_interface.h" -#include "trajopt_interface/problem_description.h" namespace trajopt_interface { TrajOptInterface::TrajOptInterface(const ros::NodeHandle& nh) : nh_(nh), name_("TrajOptInterface") { - trajopt_problem_ = TrajOptProblemPtr(new TrajOptProblem); + trajopt_problem_ = trajopt::TrajOptProblemPtr(new trajopt::TrajOptProblem); setDefaultTrajOPtParams(); // TODO: callbacks should be defined by the user @@ -87,11 +85,13 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni bool robot_model_ok = static_cast(robot_model); if (!robot_model_ok) ROS_ERROR_STREAM_NAMED(name_, "robot model is not loaded properly"); + robot_state::RobotStatePtr current_state(new robot_state::RobotState(robot_model)); *current_state = planning_scene->getCurrentState(); const robot_state::JointModelGroup* joint_model_group = current_state->getJointModelGroup(req.group_name); if (joint_model_group == nullptr) ROS_ERROR_STREAM_NAMED(name_, "joint model group is empty"); + std::vector group_joint_names = joint_model_group->getActiveJointModelNames(); int dof = group_joint_names.size(); std::vector current_joint_values; @@ -117,7 +117,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni } ROS_INFO(" ======================================= Create ProblemInfo"); - ProblemInfo problem_info(planning_scene, req.group_name); + trajopt::ProblemInfo problem_info(planning_scene, req.group_name); setProblemInfoParam(problem_info); @@ -131,11 +131,11 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni current_joint_values_eigen(joint_index) = current_joint_values[joint_index]; } - if (problem_info.init_info.type == InitInfo::JOINT_INTERPOLATED) + if (problem_info.init_info.type == trajopt::InitInfo::JOINT_INTERPOLATED) { problem_info.init_info.data = current_joint_values_eigen; } - else if (problem_info.init_info.type == InitInfo::GIVEN_TRAJ) + else if (problem_info.init_info.type == trajopt::InitInfo::GIVEN_TRAJ) { problem_info.init_info.data = current_joint_values_eigen.transpose().replicate(problem_info.basic_info.n_steps, 1); } @@ -151,7 +151,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni ROS_INFO(" ======================================= Cartesian Constraints"); if (!req.goal_constraints[0].position_constraints.empty() && !req.goal_constraints[0].orientation_constraints.empty()) { - CartPoseTermInfoPtr cart_goal_pos(new CartPoseTermInfo); + trajopt::CartPoseTermInfoPtr cart_goal_pos(new trajopt::CartPoseTermInfo); // TODO: Feed cart_goal_pos with request information and the needed param to the setup.yaml file // TODO: Multiple Cartesian constraints @@ -177,7 +177,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni ROS_INFO(" ======================================= Constraints from request goal_constraints"); for (auto goal_cnt : req.goal_constraints) { - JointPoseTermInfoPtr joint_pos_term(new JointPoseTermInfo); + trajopt::JointPoseTermInfoPtr joint_pos_term(new trajopt::JointPoseTermInfo); // When using MotionPlanning Display in RViz, the created request has no name for the constriant setJointPoseTermInfoParams(joint_pos_term, (goal_cnt.name != "") ? goal_cnt.name : "goal_tmp"); @@ -192,7 +192,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni ROS_INFO(" ======================================= Constraints from request start_state"); // add the start pos from request as a constraint - JointPoseTermInfoPtr joint_start_pos(new JointPoseTermInfo); + trajopt::JointPoseTermInfoPtr joint_start_pos(new trajopt::JointPoseTermInfo); joint_start_pos->targets = start_joint_values; setJointPoseTermInfoParams(joint_start_pos, "start_pos"); @@ -200,14 +200,14 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni ROS_INFO(" ======================================= Velocity Constraints, hard-coded"); // TODO: should be defined by user, its parametes should be added to setup.yaml - JointVelTermInfoPtr joint_vel(new JointVelTermInfo); + trajopt::JointVelTermInfoPtr joint_vel(new trajopt::JointVelTermInfo); joint_vel->coeffs = std::vector(dof, 5.0); joint_vel->targets = std::vector(dof, 0.0); joint_vel->first_step = 0; joint_vel->last_step = problem_info.basic_info.n_steps - 1; joint_vel->name = "joint_vel"; - joint_vel->term_type = trajopt_interface::TT_COST; + joint_vel->term_type = trajopt::TT_COST; problem_info.cost_infos.push_back(joint_vel); ROS_INFO(" ======================================= Visibility Constraints"); @@ -239,15 +239,15 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni std::string problem_info_type; switch (problem_info.init_info.type) { - case InitInfo::STATIONARY: - problem_info_type = "STATIONARY"; - break; - case InitInfo::JOINT_INTERPOLATED: - problem_info_type = "JOINT_INTERPOLATED"; - break; - case InitInfo::GIVEN_TRAJ: - problem_info_type = "GIVEN_TRAJ"; - break; + case trajopt::InitInfo::STATIONARY: + problem_info_type = "STATIONARY"; + break; + case trajopt::InitInfo::JOINT_INTERPOLATED: + problem_info_type = "JOINT_INTERPOLATED"; + break; + case trajopt::InitInfo::GIVEN_TRAJ: + problem_info_type = "GIVEN_TRAJ"; + break; } ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.type: " << problem_info_type); ROS_DEBUG_STREAM_NAMED(name_, "problem_info.basic_info.dt: " << problem_info.init_info.dt); @@ -266,6 +266,7 @@ bool TrajOptInterface::solve(const planning_scene::PlanningSceneConstPtr& planni // Add all callbacks for (const sco::Optimizer::Callback& callback : optimizer_callbacks_) + { opt.addCallback(callback); } @@ -366,7 +367,7 @@ void TrajOptInterface::setTrajOptParams(sco::BasicTrustRegionSQPParameters& para nh_.param("trajopt_param/trust_box_size", params.trust_box_size, 1e-1); } -void TrajOptInterface::setProblemInfoParam(ProblemInfo& problem_info) +void TrajOptInterface::setProblemInfoParam(trajopt::ProblemInfo& problem_info) { nh_.param("problem_info/basic_info/n_steps", problem_info.basic_info.n_steps, 20); nh_.param("problem_info/basic_info/dt_upper_lim", problem_info.basic_info.dt_upper_lim, 2.0); @@ -400,18 +401,18 @@ void TrajOptInterface::setProblemInfoParam(ProblemInfo& problem_info) switch (type_index) { case 1: - problem_info.init_info.type = InitInfo::STATIONARY; + problem_info.init_info.type = trajopt::InitInfo::STATIONARY; break; case 2: - problem_info.init_info.type = InitInfo::JOINT_INTERPOLATED; + problem_info.init_info.type = trajopt::InitInfo::JOINT_INTERPOLATED; break; case 3: - problem_info.init_info.type = InitInfo::GIVEN_TRAJ; + problem_info.init_info.type = trajopt::InitInfo::GIVEN_TRAJ; break; } } -void TrajOptInterface::setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std::string name) +void TrajOptInterface::setJointPoseTermInfoParams(trajopt::JointPoseTermInfoPtr& jp, std::string name) { int term_type_index; std::string term_type_address = "joint_pos_term_info/" + name + "/term_type"; @@ -420,13 +421,13 @@ void TrajOptInterface::setJointPoseTermInfoParams(JointPoseTermInfoPtr& jp, std: switch (term_type_index) { case 1: - jp->term_type = TT_COST; + jp->term_type = trajopt::TT_COST; break; case 2: - jp->term_type = TT_CNT; + jp->term_type = trajopt::TT_CNT; break; case 3: - jp->term_type = TT_USE_TIME; + jp->term_type = trajopt::TT_USE_TIME; break; } diff --git a/moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux32.a b/moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux32.a new file mode 100644 index 0000000000000000000000000000000000000000..52720f64e7eeb41975d20ba6b10060e380e6fc8b GIT binary patch literal 532260 zcmeFadtg-6xi-Eh86e`|#5yQ#W1Y4`8zjaA22D(?0RjXKkb4kgAtVzL&CO&Y*v14* z(z3f5pcQW|J=N+t$J5eZsp8QpS^{VYUh1tjqZvexU&|=`uc`vfpr2oYcQAxZQPR^tY?la6HjyI1a)6lYAq=d&Ee{9UA-lPMMK#$3`RJ z--1TMn=bu(8#Mp#_y1(@S9HLc;WA>s>K%r2YrX#6R$w?E-eowSzFYr38ZsuFebksR zvr7NI?lUHg|AihgCj4xt{=HIQOo;nU^c*$R?~C^v6KCfc6X&isCYDY6+rKRvjfr>o zjfuOr8xvn#XH0zaurcvSM(j5U)iL%&oi7+J@>i zhBCp}rc7(rv;~yg>gL*-`s?Y|T3_9sIg6(DK(MK$R=IVwtqD}eOgGR}W3#Jit*xn1 zWH7aA(~Z?_bq(tjS$&|jwnLd(+ZvkdbkGjl)X{32T5DTYU#EPV18Z9~zm~?@)s4!n zrLnzPCA6lc`Nlw7kd6(_4Z-#nb+;#=LULV$5w z%UZhCcGT1dRMrEH4NVOyL{nXLO|Yd+rB=)&t?pP;7gUm~X>XOhz@Vktv1YaQt81=p zZMc#2H4VYGfMU|v&|Di(NdS+g4wZx(fa{DU3(6Lku3Xwu8(5leELoCYTDiDveu1%a zep8y21%V1Vz^-V0%qUyF_14X_h z(A3g)lS)KWYez6}3IQmqn;7r>mg=_lKr;zoD+$y!G{>mnK(WQAn|9L1Vj3Gq%sGy~ zNFkmJv}irdnbCDrZMgN0JfvBV{TxwY4Ivn8<}b*vC0aUMQDCM)y~QTn)vz@Q{`BJNWMuM%eP&(5!g1a zoQoD0wL0D@AFUTEdpjeE(Ur8U&0km=?=ruoQM)v-9JJ&c&^`N|!4s9*hp&(9e0Y0s% z%Rr!0Q;X2*9**K|5JveJZ00`2v)#`Gz1?xX$NSo%?SGOARq z;@lgn8yaD&8`DUNOgjsbR}DQvjtX_6fO$sQp@tLsYidK1`rLlDvq`k?aeK1 zO_W1>ZHtPgy|ra6?TsyK)DUq^pt-58MGbZ8uW#0a#ip7X^!s$vzAKy6U=D7mgX>yW zY6HBR;|5t`W~i37+M1vmATh1AYH-zBQ?sUto~<=EG%4N~_@N7@Q+u$v7VR26G1}1M z!J7ItP3u$u$fvPg4Hq$%6}PrP6Y3=cwA%y7w%V4~pbF4d+uGK$n!a^9eKfYQxxlyw z#+p%MU|kKyrOLl~jSQaw2&UXx)?yGTrrHiQ_(Pi~D6WQ!7*2gt(3By1I7EN77qlQ9`dpWM$8u<@IJ}WMClzf3f(0znA#^UhnMeOYoP^ zs>$683Ku#Y4lGIN$6+KIqc+1R<7x#SzxtbMoM~W5BJL@#tSGh0e4gXCY(y}J)##gM z1%0XRzN7@h2)}D}`n*=9(^~1vezn_c<@&tK^}bJ zcSEi_DBpS33@MLyr93>=Tvy+ou8SXI!JGZ>OxYU$Se`FfonLT*W13lZzF~Hr@9f!^ zw7BE<*L;2Dwfn;FMqmBQ$OsbbiLBQW3m=aD{*#fBt)X3CVKGpDdXBoR9lnjQS>;Z1 zD&xs1_d$(vp#taAYHjmvBDlUkzyFOyQ@c6OvdYeKBK7{9Ykj8EZI-#6UB9-LB$-nb zizTVuSA~y^Pp@KcZP)yqxAq@S4DX=?hW(S~L58b_&(J9tPMZj+`*X@uBPoep2cTQ! zE<0^$-R0 z- zEPRM2HR4Q0#{K7n4~7pPIvCzFG&pop3B-jc7eW>X550lkpv0}E(UHNp?_%63cHDX0 z>Cj)TPu5?PM_x=G$+kSQx~mYU*UB`5z9gpqa;0ygAO6Qeu0JU;mHGUkl*y4qBs>^N zNs1&cLaSF~&SAcWU6W@bG`!MG6?{1DSkBE^k^z3g{61pj=Z)B8bSEl7a?5#+n z{|QEdS|2Lhn*`Tl=Rz~lEOqwuC&4lMFJ13wFt@SyssqwqFnC$S5i2iSq z_TU$~Jt*_}RC|y>Enhfh@{I0PqxGv- z^Y`qOl(4};t#zJ<#tdyr#EB||;_8MqO=x|@ znHWhJ8XTTXeuoB!Cq*s*l|SN~IP}8nheuS5$M;Wg_vWDtA_?Kc?12vrMy4i{KcXA{ z%|}p z)0@bmM#3b$RVuxSk6I+?+>rzE@+2|rIIJh(z9S~a^jIAR5=(;FGO zhXU{0)8T%EN~nu~rXuu;>w&NOeZxzP@W+vBjh_9rj`;jVhN4mQxZxww ze)O{Ff6oGdhheP$m9c34{L8$lieawto5p(E)D~z=4+ho+ zjdUy;RU7H6+uM!wwia5_u`=v8(wkd?fpl=Y2qV;*>y31b>(w%Witg|Da{*|W&xt~t z2mI$V!~$UX^Z7h}an45B6vIeGZKE5*vz=qjoi27X1?o8x9|$g_<1-UK(#O+zVYeUp z@yWoC{69kr9`dt!&`vXdm*Yn|`#Cx;UfXX82y8QHNoVt>-S#^hW;<L@I5RA(Io&&jrtgaI+tqpKZ4>-rZ@ur`1S2$IcSSKRyQ9<0VD= z1k4@uLmvnHnRi=;w4Vz*WpDd`4rZpGZuI{mkX@*4hcWgf#5{G$0O z@BHe`OFnnS@%;&Aqc6+s^yPxe>F!NIn}H$0G0+X<`R zfTW{)IqbWEU`saESs~BHQJ%fN58zh>UPSUDmLM##96X7Y@aOQjIJ8aiDhcgSSZ;n; z(KC=#S)qr`N7qYUth2Fl&{u}W*-AXV-{J0^g$A0^fx2)pA!s!?A;mll5?V1FDTJ3F zX)~+{`7oAw7A)YI1Qq2JGYRS22xCv~Wh3rQ+u>>cB~g$4k-cpsI@e0e z0?Ul-x6LnrPpbJ!cOg=>o__hh&QRJ5q1>(FV7?kk3CC7vtn;h|hI#fv3p4Ukr)aj+it=-Bex6GZ1rw*o1@leT?(U}Ko=wDli= zjqQUI$T~@6$YdbHBmw*1OmMu!AZ#>9%tplV8FgU1G{D70HOfR$)u z4#UoHjE~`_0ipS&2*Rk#ReQ5x|4xvB8=FNdyKltZ_Xhek=zXiLDb{(aXjdy;8NV)u zx?$x{an8)2!UlXlm|#gQ*1}94>70g`SvZN#Gm)09FwJzHl}949TS~2xZLN9$y4$K& z1+1&R*@wDs2FI5X08NLz?q^LxQdznt)TaM%g5`0*fdy=(InZ2{VJ(FX)(hRUSmQz- zJD@!;zYxh`D(8+kf7-LxnNx`N=xwwYt=0D@2`YEzI>MsfXb3X8oM|S$a`Jrz?kxu}FzFj~ zZ+?_q;G$ZS;H}Q3s!1^i+?##~3J9kYrMw?>q<0VH}6+TKiB+= zo%_%?95bHF#yqzBg3*?RJx(%n7rIV0ERARqj`Y0FoIfoBXt!4@6>h1Mjq z@jEB6cFs)<-2tJCSA9<;&x7YQ$YUA=##B9nD9zk2jG!e4bAJy+ zgf`Z_CPO77>D^T8?S$27KS8({vfr?IkGU^cXWctrTmdM{qJ9~-L zNi*#nDFMr$%wkFOpT}Y~gXgig^HWz@NzUy0IkF{Ha|NoVd&^JAX@{&b={HTTcx7O@UD6Y^E5bp8Yx z^;4Q=+AWbuBKEnFl)Vr_hILLJVkaSlOwpnqoB6jH=oQh1p!rycj@*gb?A~09#T{EZ z>;k(xo`5t*W(Iv6O6+0+E=Dx|1yEQ><9Rrk7l&NQ)@R|pleUzfV@R=Gsf_9WDQHxn z)CFcL1%#HLjg)m};$+kHbL&D?>-ENi>Hi6&>d*P6w`&`hbV0_pp{Sysb6BwNC9L$8 znt!gJ0po^!oO71S`YGFp&LU;8m2NUJt-=ID&ZTBsa$=hYL+mR2JdWd7Q#w^Qx!Rj zAeNJ!Jv@7IuG^E4NWwip5)yl!Otxn=7%Ub;sEm~(7N$rh8T(iD?5|QQg2-1PB<+lT zo|){`Q!s-Sq@w;31gKw%KUyQNVPz~4@2Jh5C^=%v!4hu&Azd1wT@(XW3n zGE%H+mHC2>qn~jUE8fdTlZ$+Da5bRv_0D&YY;RpdW8*~)&E6VysH`^K@M3HKVje5- z>eHw=#8#W;HKt$MSUbI4|21%!%G=Tr^tRM_OBR&OE%Y|&%YIeYMgF;^+`={PDW3X|( zlPe&UA7xFmEjt*EXAo&V4f5FhY`cx|?*9|(ur^=f>DEoh`X?zppc{3E>!_YM0_N)r z?~*dA$_)O0n%>BLYO-Aqs?4n9X;_a$I9Dz{ynIVl&iB)AhJ*8Tniy3Kw+Q7 z8e;+k|26!$23sJwLa+{);4+MM;uOQ!i(dlr^#>s7|0sBZ?x0JAAL%lH^uJVaKHcGe zmH2O?I|lbZ5dVJ_{|CfhzaH@Suk~fm{`=SZo;gno)UO~FYyYgdqYuwmY&g0D4$`%t z=h;u2jMQZ~sfSGHh14iWcS`0Cwb6`l?D|Z-2w>{nYH&HMxx7U`JybM%^|)h`?+E>R z)g;#3re=<&9>F4pWAxLjX^3GHZ99A?$VEnHyL89D$+w=47(QXBxei0lAciEZNH^;* z;^*KQ{TCak~W;w%@Vfs*p^*_~?AXEzYdJs)LJO?JEAuJ4x;XcA{Up~X`@)Z!a z`w9UF1Cc8J^rRSN2Rz~0PE^c4vS8{;J)h1@9SkFd~;(-ZX*!c`hu-ompBHX2Q zZ6XeUt&8nB>!L@Zd;`uW7}PpnMUOS!0q0$#4k1@WSvczR;50!Jvz%pm&N4f3Zi^#D z?UV~&I)%RJpyxP^`fglu^l=%>(YMFFc?)>UT7k|zs!s&te{94L4u!e#zQEo0&*+Mg z@w5@ArA39aBslOeobt2~)R6#FyAd2+7^9YjR7(dYHh#?_f54dt?Zg2m=5?W|0D5va zY&o;so7ZCWJ1`*+Ha@5%h1QJBJ$-+0_x=-t$rimnbCq{*9!XGwmaE5{QUpuLqbq|w zE1YVWbIM4hRmsXt&i;#e`Et1Eh}~N*C0F~*lM+7^KH~g!_+6a*fUZ#lmS;1hU_NV3 zEkHQd`)${&^3 z%n#jtzr|o^U_ugn_zX;NX#-5TFd=bJ^fvoF_i&PJl<=1fsy zQ-!Pd0`AFUET|6IiSE7@)Ree#!>rd@VxZs#-Mzm>E~Kn+_mc zUZfJNs=0g1TreKjzDd)-#tlt~<@`>>`5cS=UY3){)_m68=fN1~zhBV*9|jZum4ZGC zI&n%thq)B}j}~+z0{``b{@97iaJ3`nd?h*68g-wk1s;741*}UPbu!!G?wi535pC=M z*dkT3l`(-urHXY{-*NZm9rRLFCFId1md^$uc?7GM-wfsIhON<8A1b`uh&XT%7zei4a6^-W`NR3BlWjHA^m7b9V$SW9eUL5WpdSmD{UH^K|Kyq-N z?M*sFUc~{e;CUePT4`=%z~}yX+GMtV4a%Q_X-%hQXno7qhUi=OD&qmj~sHh%hqof`Uol&e0fO=ts*6jyu*vn-Oy%dA4 z`2d_Sjy_DE{m&|E+Xe2KSc#4|k_0F4c zAu$%pCW#EWQLlrbhnf~~L|;a-+;aqbGTgxI#^&+Onf>`o?g>WMv zsG6Cj^~>yh$f)-rkt&lc7H*+!fti};kqKmAE4m)e4ZBjM<_{-C zK4(oKg>`-k|LS!+6Z;pY>tdvRCmmHywx*C^WP%red-msv;o-Dun7uz)q)rX6ift61Uci1EUe=tC0!G;Cd*EM63%R8TKE*SxePHqn^Bh*C-C^ z<_O0?`%!Qn94XYbTb&e58veZ0#CK7LaOM;1r^CJvV?Ff{>t~hEH{yIy+LK(}p2&tv zA;x%RXbPS0;efYZ|23!jk)EM9a0X%MRWuP{jz!)#FUo@Jz=T5lWof#5IWggpN)n)o zUJ0u%@*-Pd>PZao`AU%Rta7MsUNO49f(oRvi0h{J!=LM>EUI#?fW1nmLaw3WdPb;5 z@8I`5%-k%F(~--SI_Uz|EI4{Y`HDVpCRO%{fyHsp6K2&X&YKs>sC)_;V_!=R`nxkn z$H!AM-~lOYBKWr=(fK{79wWhN*k{Xr*1U-R*n3xFlIVP{wn9y;^X8e{+qoN_IcIlG z9GC=2U{Il$$$?_d06f36GEfv4{y%6bPFC)}!HxmyV=91-T_x_FEzqThR27d5LEn%s zGZT_?4oswyMz8ww$cTBInj3xm1awc2CzT#!$bQUfJmxena)DC6k)X#}uo}@$kjLh8 z98AgxPL11Qt~~{h)12Ye#(AYhe5J!p+~Ar!TR`l)pm-I-bVzSDAN;|PuEdEXs+kTiPcI7Ua^TR1!0YK_-VOb>f< zA07$%=4Br=m1oy$GF^IC<_jtjQQz_ZvZ``x4XXN6YmU<6++VOZ4CFs9Qv~Ixb@i69 zQAQuet^pL29V;~y>dQ)kM%27?AVI0`Ch9EPOOTnMw&z2bT1K45;)jgLwh=8ON$@Lr zAS#m|HRFg)f&9_mV<+NM^z|QXPmdvLb>6=fr<{hr9DYL&C(zPWa|=W-jfK*5YwEuc zt#=9<0jj1shYhHeI|Ij%>YY56Mr|wB+J;uC!n~YH3$bKXnpzjie0e1sIG|f^UZgs+ zMqdHj%OdVNQ46_?wG&vWw6Ij^-e_a2TS>PPrrv^ov)hAi>85*nT7*` zhn!SL-JDr})a4bu1%|DZ_utc=%vZ#^{ecKRwLOWx_o?Oc54I;CA`^%)7)m=4SzsJ` z6NB#2BDxaMMTSBtkAo<-)Z@7zzK~QeXZb&im6_$^3yEEpIY$)|Rz6T(l$dHBOg+{> z-6++?W53ZOujZ)YDUT~2wnVykPTNT60h9Dty2VhDnYr(oRqu@!4_?Vsvzln@F)5}s zFpS%a{gnDMla#DK_7Xydy@W8n7CrKxs+~ZWG>PNH=)k)O>3>!Uk+Z-uUt=g2Z>h{0 zzBqD0)PygD?6Lh*L;mClj&2O6NAPkXNBYqPAThjHL~r-v-DBK6Qfqjz$Jf!++@5C4 zTbe(=;Ht|EZ12rcn|$goBU4*P%77i2EB@EE?DXppqwhv!{r5NTPPcbAzytE~Bnyt; zyW5Xi{|F|wnEI<0mhEH`e$&Oy!6cs~*)!0#zp{4+x+?56;9@sI7-07u(Qf702!X}A5b zxHo1`ZUyMtNFa|*M~vU&d-=226M_Q=N9W_mJg`j0@9{ZN9>0RS{n-3$yN&Vg|HvMn zz2id}+3!}+Y}?uJFnzY2dvp_8OQA;_TPKOddAB8(=Pqv#*1>EY7|j=H+pA z7-J9LO^JX0o;}gA^k*0w#esE{d!*lsBcR-WFwTDOIQx!qb~PLjH-nXvu>bmqf1}@EMO1}iJuv}_fm!4&SI@z9q;PmC5f5K*nRgD>F;%C4x1ALBXAZ{eo`_CPB5xXNKT1!3x3a z1-~cwBf*CS2L*pE_@-bY_L|ApE$9`zP%v9?uHZF-0l^l*n*{B5Zhk8EhXnTuMg;#u z@DGCT3*vPvm7a-$XA6E=@N0t01g{hPrr<`w9|`_K@L|Ch1*3xYyE^Bf0iztgBzU1< zzTi^9<$|jP`BpZ=Z4>+_!Ji5~CHRcsD}uvrLf?$1}y5s?37g4Yr8LfbdR z{(|7|1RZF=Nk4}Oy356WOmG=Gboy5aUN3lqU>6Y$davMj1h)wO7?^-T#bTG{Q!RL% zV2j{mMD%U_VjmEELGU;*;fscGQtUh%!F2fqFBDuLc$HwW;EjT}3O*?q6+9_884IT5 z`+31)!J7oP2;L^ROK`8?F+l^{ROB;3@N>X~FQKm!`&R@n6D$?HTCiHMP4Ihy-xvIq z;IQB^!Q+Bgpz&t>3k0tcY!Yl2GzGT{{zULm!4CvKg8>WqeMRt6!7{UL-5VCIVvoHFX$6IqZ4Ln}`T;oLOGu*OsQ zzGWBT08}1AV{eCNcDho3iNJ={;YsXBUdTNpSk0hy(ma?`Zt!)2w-A6aV##L*{J3~? zCy+;miM+t$d7yfG5?C2pki_FlMdkWkpq~9+gdBnoL%s}T$X!5&+yrDu`tx}ZrFO#jP8S(jm*MTHjbHtuN?QoUgS642RnLh8Y=6LD-Ny4^*5g(93#Hvez`LG+B8cWrg;*j4GB5d(monxhR<7Gr z9!qrItOY19FZNaE#;G#4_E3TsvzWQGl?9CC51fD$$*V_Q6Qiz7wH5M^{8t zatwncFi6cjo;jkJn0pa6h_F~i4(>Z)cJ4dLkVj4v@>*BlYhAN-HRx6GS!D-KATtFB zZgn0wX_h^A!aSJ$s@eJ6N!Ez4T_bj@GL*ghT|O4D^#u{CoKFDyyvpHiZ`Beht*)N#JUoUB6Hsow4@gPs1lK>Bk^rCu)tGFOa&FMBh0rO36De6${I z*smI3sU|!q(Z|!jtiss6R`Kof?N_afS46&5&i0b-!^$1++Em0f zmS<-FI#>;&At8EM5!vk;Hu7NSZY2FHk(}K?W{F6qL`L=qkSpxWBI!N=j%E!RItd4B zS~dy^su0YvZua05!a_Ep(nul@BO`M=F@>;``7U6EE(bQED(IQeXErBPX{3W2FM{q_CTdqC(otYzeCq1ICkaG9k`ek@xiiwMs z20`-T>xUO%Q#QP(V`3y69(?C*Y_){@Mk3qQUVFy`{VGz3-EQ$~PT%nP7^PyL4s3b) zt~UeR%;!ElWWHxUL>lY1Wc+*utH@Z`5H``5XW4szc|$E{ua_ulf;QG1c!m`H*P$-2&}$U$P4-a zo<;nP*RBNjqmX#up#WGK!aGYK;yqi`C~6QuTSZtMD}d-x7P}$Ap8c-+xx}MMkrZG3LKy40P>T{Nv)?na#fJB_ zsib)C8W1~zHH>5oU@5^c9^*q$t8)y;ef z+r*Go70kn~4|A$~xrh2gC62C_5gGdrsR0o1GYt6+7b2p&b!A5OufZCJlDp@j;te74 zP-QHJe8jNbw;Vwt&V4Y|EB^b;m$Kj2{9hTzzgP2LK5Zs8_!F0V0C~8t0F49~yEiXE z
(d?rvrnnT@dAYGLq&$mL(-+++aJF~?rtRzz@lhlzZ^A&gBpP=Dz-T{IE=N-s| zL7C`5Oir=ie93&i>u2bGnLmhCwYfLBti{afpC#YsiSCu)p=14aC|AeYE3vXESE5YG zQk(eZE5T`_F{%VgMhh|!H--<4^XKE@lwsA?PRVJ`)xK^&lPd96-Ek5b*V*8iTMo5Y zI_66`%Y7_7Tex4gVIcK&?a8v`kbLw62V;$6SQ%+UDoBi=500=qe^%v1{wo6CS4l(Mq260RH^mdMRz#i);^Fq6P z%Ml?XIsgwwL=lWeWKV-Osi7H%P_^)nb&e?rz<>;(Wv9obY-oGo&H$?z01+$)GV4S( zyk)>j5{KRh527`u z_i(RzB?R{E$_r2c3h?Gg4_8?3Rzt$@9-N>Y9Nwgf55hn`JROEhH*r)|f(er%h=TK= zVw4TJRiJMpa;`=!g2;%aq1|e#TM7DH*h$ZNL3&md(q{lUz&wVma>8OYwugkz<+6G-`RG)DT9 zLeKD|?*&rM^p6d=cTv^!dpOJ!$261`)5tUtS@DRBgGgDi^P{YYq$iS|b4k(@Nxxmu z?^Z~<9k7#*NV@$9N7=nhe(oo>`+fuiTLKoA^|i`+SUK|C1}Kr?Lz!-ptR;;c9$}h) zCN@>A+cF?_v~nBUu*3w;M`2ZOa`a86gH{7;66C@-QHR*kR6yLcvUpTdAl^omG@Kb# z#fU5bS+j{$oBcqJmx&zW5b4i0iT+eO4xLT{S-g!v(y^uBkcsNTtaIK(_39P>PVrv_ zcls0Q&-qlvsJ_?}9=y#hjD~?Ev=g*j7=0lAd5RHkqyjQQ^k;&&X2k>%Wg;&VFntmz z+a0`&Wqd#AS$5QWhGWym3=^4QBAYg%EZ|@Qk@;fgYkcJlVIZ>*^%w z7$GI)u7}*X-L$|TS+FkLpZzr3GE5NuXdW_O?Y=JDug--?N9?=eE9nt072-Gcp|B7n<+LK5%HSxzF6&?Zl;)4~7S!0_#xJXn;71 z0^HBE$%yMp7sh+^wn{RxUof9G4|KQ6cx$wMwbS!$q=)T0)1!OWVb{Q4PtW}9myntv zm6nH*mNCOVJ1yIF4={h)jAM!OJu?pU?LnIL$n1+)cP<8KZy#=IJvvyEfw*sk58-b)JvOm2aNIKRE zyI|e1}79FY$T>&Ta80Cqg^Ui$J+8biEcNq>r_m4zt*4 zO~lo-NCv}V<_eRJ!!dke z%7HsibX#L}S|@QyJ#1tQaWJNcGbiN9GM^s4F#CN(gB7h8L_8Q8vZX^FxUh+3u}jpl z7|u0H(7$tK3?eO{AoO@Z&G6sE)!J{cKZj%v4t>Nqwy4TeT$RRnfdd(L-{+DMZU_Sc ztvFc42BA7wJ0Unps351eKn$TD2K0P{%SgCK78yeNIaX5X*Yj8FGRz8?C#VtUt=8A{ z>u*8{53U%Y!{dM=_9kMF?u2kZ-c4AeusZx4Xbrj)Efk>)LZsfU2U0(&kJL}Q)qY<5 z86o}I=+a*|w)U!4xeH!gaR|9?FQzy9^im{cCzFC`dWFq?Ala}wknSWf))pffIvVLj z%BAC5#cWCcFHXszrFgi^I2AmQ%WbeCmp{P{3naoe4F8c~7v2}SOqcyGEJ(shFC$p_ zPoJ>Lp61Mvnq+u-U-Q_;}X}c8$#C=%N@} zRuup@jREOTVaEH@&QS%WKq(PPH$*x+_ZhlSIkF&)>b21DJc68%7pMJ9+#`zDHf1Ld zy2tz5l2)TF`0EnDg(fO)yMfxS#t$r!qmmXP`LM%cJa+F%{)|WQ5n-qe2y`G$q_t;% z8K@5+)PQQKDS76V8o+#zAH$P^{E6g$1jzVpf1=0&R2(m1vS6y1Kz$Ux);S#h@Zi*33Lh5)7!ksKC0-qgk_1l~fxFS+}CxU%X+oUhou3vY4E zz(tK7yj?9D7`VF$6F0lvBthDI#@6-I$dH{3+%90hV@ zUQxe_X~L_dC8|BK7bsDcS=sP@Jcu}3W#3c^WUCun8GtBRP8#6}7FW&_@D>KFF|;9DU>bLs&biqXokNmVw+vt7kAIu_TJ*d9yUyBNKy31;{m zLO%>-cv}xyS!rh}QqOEVD;>w~tkevz8?4dzy{fWrQadyZuPgs1RefkbDd9f=%7!F5 z%sk{0TYJbONU~r-jQ4{RJ4?se`esG-ZqmQP5d$?n9gFmBL`eSsIzGg z)^IHsvxiKa0J0Zjc1cep{Wc(H%KL$=aav96=D@C*k`U0bEn%B@6iB`YfaJ@@iF}y> z@?|lSFOhs-CY`Rqk-llj1;)S|0g#}AKIRN=TLEC_B4DTqu86Fca)hYixM6=UvhKJP zQ7|bZVnk8Nx1J0l}( zTdRP)>8=*(I$it2aTFU3rkThz5Y;>wSX5t!ko7k)IKO2g!=Y)P$}l+^eS6GF3$;D% z-h3D@5O7WZQDnd{pGVfpV9GvV24BJs^GheW9D77o3!)G5U7>JvJ>Q-TN6P@QJYbbv zCnBy59Xn*^5*lV1>Sa+B=`loe=%dIqWUy9c5Q~h!ih9<16F z)+u`)o75dFtT0uI!yxI#t`9vSLskm8yDlPSj1I9E6!}>?8tY?4t zsT}l>6}O3&SeX^|=OP^lcY@)N5@J#P3^;yjc&v~zjLr&j!m4kcYc54aNk$2;LYG!+ zKJEdHskYmobI(A6)(R(PsP)qSMSgeyG3BiA!L2oNZQiG^y7Sl#A|nf~x{qDI*A1Zc zb$k8Zs>sTI$qaWd!{P*z#>#5tZpNXZe31eFt3`2b{lDQOJC*GK&ik&tuxx z-}N}UYdtRCus;P1)LYkMPJXCKXdd1aqjoK%SUPdR%9tJ+LOqGF1M0H`(XDu~SIrL# z;KuesS8IDoXmqKFO2>AE`DXQHyTR(qvjQdfvI(5XHk7g%_YrPW?K=-9+>JC)z1S*L zAowm7e6*WB3OkjD-7)DH4e96}TXrvsUd|WNmiReW*^6=lfllvebEDc!FgPF#C~6LZ zKL9d<=Yfo1r}9V7g$Ro|Ia0J0Hyt`AUAGO?ab>ybI}uBr@qtB9qQEFzJ*5lTLpoo&HQZhekT-9WHpO zq^CSkN^eF{983Bxm2|RsMA$GG>6mmzL-zD%(izQLu*dko|CsV0Gm(rwfVa-V>P8h@ zxG*@ZXXRYtadcd-51>WV9=$zFU(ivcYZk_wxZS~5H6eHwSClx*pBcRduWf}tJ~U{b zNJG6Vt>1(4t-qG4d%A}49emvDod@t%<@tO|EF66s?{mR+h%ah|quc+WY~LWf7J04b zs1FNM$@r<=-&J5*Ur)|KU#-1qF6|iF3a%gG^g;A2gnk569JX`GjK=7}qj4>EzAs-d z4m{BfPrKPhRVz5DZm@p;pTBcH*1L>4YYx^gj5_nujVlvYT#e4{e$ZEr_FB<1KGv#m z7-SrW5jpW-Qdy0NEE6JYA5qm(AQxD5Q;#(V*hx=R8xx8S_gDkj0j8pitxGHF4cINb zQfRMj_{;6pfM{ZLWMus=-!f3F2UZfJhmXW%`;@`{HD9mK(+ou(wkVdbsK1*Yr!+ng zb9C2#Xr2c2Yg80=(5S`tvh}zHmvTcMMs(tvs{f4@#=UQlLu?HZ)CJ(hD#a>7U8c^n znjQwS8)9?94HqBez&f%YsUy9u`$W;4={amBJ(2W8(w_hw`I4S=x*5V|3hbm~eo03pU*hO& zWb`n`Fx+L7rza87dk;az>L`m6d256<>BAvYIYmoh&HlA}%ge*)E_7e|QFH(n)V=Ql z5G7R+Cs}%zgkinSiwIE})ght#Cw6qBRYR3!(jE+{%Q zd0Mo%0nYJ0hw)r6W0S}w6~{4_s4~IN?wRxq%<&$n*jE+dLli`|d~6ZPMN4;=k}k*T zEG0@U56IN%1)EJOHEcO`>FCxs-k;h*e;<&!%VKz`Vfg5VthFR!G}~A6p;BQG9Z*@* z3(O4s4D3uC-I)#BpCV!==ugooI?derVFnzrtO5CNT!lzOp)5FHAwCNSn_#j+9@?>h z0lA`B3IJBQ$9gD(A(1Y;GZ5Lrl^STp}rCC%Qh zs@qk!ML8)x@IMARCXe>mL}nETRHiWzq6i*hCQT)qX!;OtB1XVM70~XE?R?o&QMU#y}!U!&}GQ)K7MULdf$W67s3_vn`~ zQXE~KUV=G>6xq*EWN0A~U76%+y^7wRfbUZCL*|;L#N@C@D8^w$XRoX2^Pa^VC&}ux z=buW{%nIb3Htt037_3)T;FW6#GCyzMls9Tb^^6qCAdUj5{$2ziCzg1n>BJwE+CdY{=n)VV37;8IV*Y{$_|B0RryFQza`TW1VpgMPY z;=d8S3wG^^Gv__yJlkQHDNwW!W=?ayhhRwj4uGBbcNMb`@8mOzEwV7&Y9hHh{zB3arfwja`9~< zM)4@3;O68LSen;S+yevnA&Q5stYu~v^5nIW9S4DFrsom$31%?NN$TcTExp#HcOEd0 zBXPl53wl0DaBuz+r>{t&5<<^j?^d-x-sW7o*lhFSyB&Rl-S746Ptq59@skG!N9H5m zI}A|{-~r)#5iBcbQ67cgodI6Cp~61Hn$iD%5I6A^h*WE#Idb0i6EDK5rRme zdtaNm`hyhvP>4w=Im0seWgJ*c-2S`eM{tSPFC;pt|Mv;VlP{E(Z8?2d614C=m<3cF z|CK$tUmIccofY_Kh|_$!dnufmxipgE145zP=R$=cBb4@32>k)}(;aa2Q~sUjniJKv zcp`hJ54-+7PbSSrmiZA9+`EQ*c+omRDoIu%Q|R8@#2i9JJ9!`2x2exwWEd~iT+T1N zbzKUFREWl(`C8`j9(?jOJ)oasu z+XFSm!o?+}WeexdFI!gPEnB=~fmemi#5DnR_`HGFSlG~9-RLb123i{f&1-`7?Y95y z!1T;Z(q{(@FP{7k5ZTXV#@ucO7I+()>jKs7>F_CPYiJ^k4vx=b25|pMW>$K( zX0UAab<6+~isv$;sATaHd}rY@ueT)7s54-*y3EKghZm?$>&fs;4aI`ba+2BnmL?>g zS+8!3Ig^f_OFNnZZ4EU@T5UsJT|-SrW3VC6j>}U*xtZk@X(+<&lS2woQT<^`i%sbr=re5#Tz#1*faTK#4 zOOl+za*V^$Ky{n9CDb*|F?c6iuNQ988BwgB_BeO`52YjxYH z3BBll^f{Hk*Sk2#2}&-d@*^UEtV4ql;M?Z3DONngv8H~F_; z&NU40-2b(Ekz$`R8FMw#sO5j@8`AGyV&_%9F99n~){prDs%Ji?4jBL7e32Rub11|C z=5(=hAj2o)QjPXs((##zAL;)VT?S~_)6K$<5BdF=4)V~*9}6X(?r@f2+{)3FJYFFE zmkDy=lh3*w!|*DT{=+o!SA`$xZMr)_$5m4MVLte4z>jqHb3f?fAKQ-`dA6DUq_cU` zZu{Y6UQ8x*e-w1L&>)XZM~us!(fBpP@Ish4`lZT*X=8eEJ;oS*o8}tEMw_Dod4V7>>rG?kBqaQ0lC@_`JFS) ze*QT7SI5~i$Jukn*|}?IKjdFB&d#kF`=NjBID6AL``U5#4dd)`kwcAs!?ZMWXwjfP6 zR=3qPsIZ8uqgAE2h9e((HtUq=uLHHzwzf6V^@i3!TT_P$-F{P3U5zr;wAQxP=+LdT zHQIz&s+&~;+XA()FmO$CV6BctnA5Q-J|4+E`nj6wps}uHWt06~qP6W9o7(X<)wLL; zX}!sqgK|kgBX>LTEZkN>MCHE@^*jLuy_twcbRpWp1T?Ul(NrYhEcv@cOng^kGSBdX zM1(&VOBM`Y0p$14Zz7@tcu?$r6lAAB_pcMdt46R1m@pNW)D!U@#s+c!mf%+Lzf1hv z(U2vaXBgiiBAq_~lJC!m;QNT+;;IE_oe(B5shj&;!f}x#zRENw-jlhd>>)02{Ujn6Oi)ROgqBgPDJ=8#C@OOv*Q07vA-_% z-xEP!fV7iO36OkN5aGU-?kMX!#D9n2F9aV0l72rC^kH#-SMYtoPv{T2iI5HHJ`ZGk ze3hFxNAL>zgRX!Gx@*L}Rj@;_oBp8NNCe%#K-T256G-<*h;VP14!jTtdmzIE46Z&P z;zZ^Mka}=FWXk+i5hvo4VMOq`9!NgzMDY1{aeqwkN%4P9{67|VC(4H5&H$3n*|a14 zmua7D7#9lW)BPgD_$BR#cOUHt_Y5)JFy5m(!v9&^6H(UWGZ{#F5AC2&5%({P`$ghD zN8A^P`!aE_B!d3|$Ry!n^z)EKLIze$h|trYB2AQ24`?W-#h{^{ze7ZrpMy3b6ZH~SK(enNkwKM}O_Ka&Xe5RmTQ7kAapp5`8)*|Sf750HP(C4M#6@&4_5 zfY@g6@vFb5|9%;_S;~Cg$Svy~$jrQT_Ib+%So6ukl1whvee$pZlke_JNP?K~9j!1bKJ945k$_TJT@C1j7iwtm&1@@`Ig9p0#HZP4FYmjI=si-n*VWmH~R6kWzuJoQPSK17!V?+)Ik z@3n62g=SejEaMG02{F>Gb`Z2M;AY%QT2p<^C_GrKuF@cL-ahg6&|u_+@JZ<88{uQ& zBY1oElSmj#fnIB4Mgrgc(CXE7#_@i<@s;IdrYHq!GfRVt?D!P%OUkH5#)bN1vg zrxw9tPAS9Rj->Fr5q+ieLZ>JeR%18AD}02@ml5@C912OQ1?m&GqpkB*!Fzth721gN zg`opOdxvn)NEc45hU(0_`}z<>o5$&o<@ymm?nYksD5*>>gfZvqKKpCF?#x^`;B*-xp3_a1r=QLD!7l-e@|K~Z~j3w3%?W!a+Y>OmSSJa(=1ch3$V!F~Tq zKB_%Y%~J;JKgw*_J2(}*d z;<#)J?EWfJiYgI(S8XuJx_bDq2uJBqbcowe|4u^j$C0(PczT34QnN{(1rq z?W?aL=*wbs1uC{wOJB+hM2&kedcn50s-7k4Tj2FxxIngr8~V93TrB&%_^y#JZFJwX z4kwfC&S^sM4Ak+%(JSC~XfT>3Ug&&+QunP zO43SHWY!cHoQo~h$CT9Pz;X{-93~Tg@hPJD_*+k-4%)NdhxDe|DRo&>Q%I&iiBqh? zTdGFFiPf{Xz8HV4sUA|@lZ?Mb_1EC9%K2$oa!1aKi{~vihEWH$u*dFWqCBp~3B6c- zMtOaNZ=#IahtwCTBdYI-UI9{2@BrJeN>Fq?j6Cj$ny0$-sGkm~F?mQ<_(-%4R+tR0 zx1hSM_A;P%VOt=8y@HYji^>Zx^Om;M1!3dmYgW>O(HQ0@yTSX6f>|pE=$bXi&ldeI`1p4uJg`iEx#QNZ7KVBF} zw@eVzbM>Tx&W?)?H1o%{jP&-C0lN6d_G^TrZKglzY~HlnerLmM%Y^RpK-WQoJT@H> zH7)k+fq?IZBijW`inC`j;rBeTiuS! z;b8^NHrjbPe0wvlhHr1d#qf1){H!)^hi?n4!Ts=9p2G$42$z8?<8eLwb-Wp#i(qPj z?UY5mtC0o=1P~D1LPVGFFJga4aG&7Qf-ecaCisTn9|b*7F7o}7;4Hy9!5aj-1Ve)N z2=bs9!w(AnTJSf5M+I3yNaq&hyV=%4i@OOgm2)-xiLfnl1OM({*<_TUY zSR~jY_zl6k1n&`iK=7d8M}m{kc{84~1}U-;4jO*zNo9kBZ%g zc_ibp@4>GX`*ngHf;S8H5YgD0V&5uwySV>A>^~N~U)+Bt_&AX3nFonjQ~V3v5&vhg zDnPy$0O@}r5&ju;hySI5mlHuZPwa~Y)jj!eFQXl6n=63ivxW#hTy-FywSqSjLEj_x z?+9)c_uIw3UGT@^{;z^R1CsxvMDVxo*Z(})AjXp>m@SBAp{=H7bU`RHGb1ZII}4w! zKmB^poJ%js(1V}9y&jZt78(OQe)TsM;{!w*_t@u(dVRfc#mBK)omlr~gX$tkLjmlk_)EbJqIZTXrIb@DXz1IVy=-4Yn=k z?f2&E_zSRJ6>&}+R-bc2dVIsqiGU*I#ts>lG`Mk+ovN*!k%^JMV=xa5;)asga$Rp2 z<#6Z?J^8tZ?8$n9R|irHViWPQ=3!)xwv-gE(7=lVK_!Iu8*i&mfi|2~I?W`Ae$K6)!1ePT+>ak;6_X!mu+T zmZ2(NXC(2o89IPLkDVb)eOSBycZpCaa`w;0>@X|j$rzsE1#fy!B>34d^`_z?gPH8WVnhBrp&x?R~8m-f7YMT9)M;8k)! zF<-taD?uX4ia@jpPNfiMBagJNr$6`+OOUiqzP#`jEc7IEdJ_4{$1^~l-Y2TJF@U7o z4iRPnmww1`P6-;=@GZCu93g@55(vB#-oZ>|c!x#Qv>fQxDs_I-DpClWIFfc)b z1`U|DqXvmMfk6`!>Hq;zg9Hc=ZIl4P1{)#5ps|Gsn544Z3}8h|{qR;it)9baZHv{m zv<(*t;0Sz_xqjy&TsPUb$i!kuj{+s^)9v( zR8V)73i{SfIlfAvk-Q*z>bX8gLA&#J2cno_+IWdHDY-ho}IqQ=*k_JYP?nv8BR zXe+1|D|80{ZrzC*e=f$*lVmg52k=_S`p%umFz9n0_$ z=;}bf&i1caY3BQH+Hr*6ykMeJImps|reh6~i;%1CF?Em#6~I zs^U_;qMP4zT>lt?Kg94a>>nSsTt!6ky58b;Q}(z8F>k6upnNXK(+Q}+jjPH-=(sLZ z*9T{=*9;n{4KE{&GDtoKoL zs@53k9@2Dg`aCzMa0Cf)Lk}QCyxFg*dmXE%BQfPXsk0T16>zJjTP1tLIvx$FVlT!n z(0;0`fUjbm@K8BCl(c4Xc7vG;evn4~J3BcXNre+gv;Z)aqOpmBFKiI(R7$%s z57CUXUR?R;-ITzFW^e9)?TGd7e5NCY-LhBIrq`WxdRj>NTE7D$_aU^(yh%EUxx>DX zuazAxMkh!+>wSe@<*7F~WHJUlSD3L?S*;)1Ly%~XJq%UZH4xcBe`GFKaUOku1p5yt ztRl2XHcz}xk;aHu2(BC3ij-}c*iM9xO0kBtbxE#2^0+-L1j^1-TwIVE`)sd25=ce4 z0pUtrG|GF@I3hIg6-v~`$jSksE&M`>KjMB_%rjRp28jRL7aHz0HiPtB71|_tK0r-6 zoq^0aloaq2PP4D|*i$Wg90}nJfpzSc=%`Zs>s8=ilf}uugp%ur20nPj4es~Di6{2f zlG@eQOsIE2Y#V5*fU<|2nRR&e)REVw4=fr^uW01vv7&py@^;4;Z~YkFar9j6pDE>n z;i2(X&J;M9BwSj%? zrl&X15ovE&4w5OJy0Q3Y4&l2#_>ZCK0Rr#(3_u;Em=*JTG^F7vNF0O+|A|i{C?+`s z+HnEjMDV-w!8RU|H)hlraF#ryAYm1rHy;>YsoBys$Cs8C5$kJkK*~{<3AB zQ6dKnKfK6r)c=?bt@woOI52%sPYC}nW4)IrORzT|It%OO1~f+UB^e&Co=p7C5i^D$ z^{jExq6Pi&8HpeLyZu$tK_0sC;mAk&qiMiHdZqeR{ihp$T9eh}xgQWxlzWInv8a zzA>3N3p`7fg=@h$Zd|w&cYk_rC5)zJ1KGxC+qDhg8rLpg2DWj-(q-ToF9OH-2Jnl& zMSk%D1OmHxUgLrVjfQKS6s%mZD2$Uzijxd_^^1>}57q4!g{0aWa2(Q^24r~>rwYy! zTrc>af{zRSMsUC29|b=UOhW}Ey}^R#3yv3@E_j2WEy&pr!xG_>e=WF2@Q`4d@M8N4<_nexP8YmYuvPHKf^ z_-6(GD)@<@;iU%A!O-6n!TEyR=cN71K+4#fyG2K%!=-(Z;C+HW7u+ZKyx@z1<_^&* z=r|dEwV)$-m*7spy@D~pzyO59fHGEaJdix%D~R9`*V7(!HwxY>xLxpd!8ZlHUhO|9 zSS}bATr0Ru@EO6s3Vtfs5B(q0bsCWAIg5z&e1-N%&w1irAUK-t@K-{FKX!W!{};UL z!orJ+iWKwu^Lf_~a?rt}`MD>)(~!$WsLF&d2pbBET1jifl|)!W@~0#fU4U3iJ>}2t&Gk402x7C=Vxa+;Y3qcJ7aP`*rR|G>Vzzqwvq}8D}Zt{0FlHav?A%0gZ^w9>;GT>p$XESOjAQ{|(Na zJyxZBc@b#;TGh3?HZq`d82_7JOKaVy)9hPQ3@LrEsPV;EY3J0D7Bcw^fVy#rDYh{# zy@HuaYKYYHbO1PK7U~^%(~1iN{h7*3*dM0*8oEoZC%qP!N$+DIm6>c)o^jCvkp4S> z)bdHBKO+4x9aJI|1Cnh`r2n-*ttQY>#Q>gkb9b6=-P33&ssjJ)FnmDo`5MZeez=;6 zgL)3uj0&As=xc$2aS_QnCzAG)K&FLAcNWmhStw+%pUV8@RAZ*1NABy%$KRmB>HRF~ zL}OeG&oZDp^G*dx9|P&mJhNYvP$ULNM*1X>DqV?G;KoeOo`s?-r;3$wI_XTxW&<-x4jVH= z?K6yvC80mGW}&cxd`vp<$IOukk&3>UO1cy2PNcier1`+mu}yzQ_N~FWHp?`|qNcB_ zZf>-65_*fnv3|f##opmmwp%0Kb8sz%(!B7zUHQBf{Z5+cDT=V?Fez(G6{wd?3N~Gz zY}e9lWUn*r8r1Nq$^Mn*4KdAVc0VOK4!$V(f{3BOY(T`Ueq@*@@Btci;{yx5WO)$n z@BSWbJJ7W7AE|4 zfKh@)ud+GS-&87PW%|bZb+=sLtjM&`HJfgE^+za{Rfu?s>YNAJE5M-N?OdB_%0Afi zjbuM-y7=!$E!EE==LOuVV8TOWB7;qe6#I2zk?3H*3A*3Kwu0(%vAt1_sMzDCMIJ?x zCwb+=1e$7-@yPehy)$aXkvtE{}?} zLBVO}P^qr&&?Dr=Y^2y-fJoSGa=bC)92cDy80o?-Ta6bB=-?K~}yA`b(q8 zBQ1`*MvipU2!-BkD?OL~0_BKIsQJx93>lKD;E%lMnjI81nSiGJekK7C#M2{S5dxZm z$B~h1gYh9D_|f7CzV(md9d)cnDzbm!YW&jbsVOD9Uo%y|e2C?~Pi2gFOd5e6ut*53~vt4vxx9 zfqm4Q9>=txf?;=b?o!nY)0Ms*Pj~J^M#?FykMyBiGwDO(aQ-5dIGk%47Gezg$}DCW zx!2=;?37qKdJ)NiE&+B$nDSBvq(biyX(jK@GRrv)6)I0llxXP^8A+UFUR+MwXkja3 zU>1Vf<50gbCuXu)ts>W?HWgSq9n0rb`YgO+x58)Z*C{F6s+4WH*iMA!YO%&1M)3!c zU+TUC_Ib`NnXMnXq8rsCI&6ce=tu(FASymh;x!>bo*p(sE&j)S0{|#=zRrrPvpM)Q zd9mqgC4%L^<;Wkz{s%HdOcksgkJ<_zp%iO8%@lS&H1fO-<(}9m&Vm zv3Ju|C!Utvw&J->Y+JR(hpGVgAAl#7if}gKBFT1eLhyegi@>9fF+pqOx~*8R@{{ZS z5#3BSFKViUR1)6RrA?n8Z_cn<1e(~b7DKi&IFl^X5j2g{TNWoC%ZiYo5SJMk(l~C} z*@L3XlJj7HWS?^_q<7e}Uppb#=1v%qriwdZEqU`0bY`mZr8_OZP zqe3qaHr=WZ@tE*K+~IRKm~jf-Hqumq#;7X?1}!x-@oZg{mUHp;Gao{aTK?Eq@P*tX z)(&{qi;{kkdoV<<^qQFrI)W8QH#&loEKJY?=$^ah`a~U9L8{nq`?*VBjXoTmo1VgT zyawy@&=;Xw=;Fb)d`bi;VSxR*0J@HpEa#GCO^<0!5tM_m{ag&$4c##%=Vj6Cr;tvy z=8JmIfG;ds&KU7->=e9WxzcWCA0?BDAV;%Xyl zMmeMJHB(p1FtZ#%ukzt{8L=!!dab!k=FHkFl{sdTnP4U>I5{hysdEZlkjkmtUr+6y z8(`pCikW2Q7#Ee5@~hIF_7r#e7|6tLQ|>0Ssr6-t^51(oB5N&^Nwe$M;Eb(-f8N#p zZYDmetB<-gS^rNm*G|r{tI$KSqvAbhW}+V1m7KC*!qRjd`WeX9=>FxO&9^JQ_8K~ns!MvNj2EM|Vn|D{I=H0zyp_1#dqNXcV0~ym}Z(8~j$-ngg)_CX> zvBtwnuh%*+Rg_%kL4Rqo%UD=kS|>)l z3Va$2lSr8U=&@0lO6^w((Z%deNNREE=*1=Oi$i$yUn~4IbMVoo%tj1qDGBb1;l1FN z54u&-t%1u-CBejwkK&%y`iLVs^&024UW>~S7CWCzH9^7>2enPjKbyYY^LzG~pLj7p z(d%{2msW7W*;o2eRo#(K_Mx!>ICefz<$e${k5v%AQcNwjt<;KIX8KsdtC@b}F82hb z>DCQO=V_1lgNWa~P|-z<2+C0gShA!NgXNSfF)=0sbsNcmoEzKR36dcTj>uX)lWhKb zny>XatQ+)!cT_5sHGLfoh9=%{iO;|>B({!UimlzOWHCj*3qhUl9)<(vuK<4J z6ULiOfLHp(zk2|PP~$KR0HF-Qtb=_m6fSeVt6ArIj!Rikj797`Ahx6q*dvFG-WiyS z|Muzl%z3x~#<}A#EtM_FZbz(J=jsfiK=PbvJ^B4(-TZ!4{%BI*^P_mH z;lBbr|GqHx;`!?>5v16YSOH-eXROMn7Bt4CdAN{)3DOsDy^lYF}_72moN*zs6a;mfGvyx5tm4lvkbbLcjVrHj<_^J{6jDHf&WvgkN48~uO4lr zY#{cK29jKbjdxqWPjT5-x$Mi0{X_()HV%4~_*k;f%X6;FY<+H|djoaS`gsDYAVv7wx1@_r3f{a&aW0jr+Jtg}%ik z5d^t<)V!pu6)N5Fn@w+;&8EaZ)P(|>bwx}KM%vYTQu0?-2wNcRebw@&*Ifc{>bSI- zjAgT9GK}J^#FOtS<=PI2(Y6ZogW$ z2(Y@H@#{!&kUL3PFI^MmppUcC|KKeyxI%)ET5fCkXIXB0u-x9?^_~o6@uAdWz~r#_ zVt2IR4V?wKE{Z>sTx2i55E6-l*|Oue?}ex2KH>{XXmI&$7~}N(Ha<9UGvn_(_5$qm zN~RrYM{S;fk%3Ja&W;+xKo9J-CzS2WxQLAWOVy-rK>?h>-3e72u0q}DTcK;itGYJy zD30u8aU{+K6uy5;)yVZHoSXW{tYKSm%L+>N6(|gWkf)@w zANOAqD`CgTdOkC6SrlGSmls|l`g1R+rJ~(=P*l5kVII}0QOzuL)u#M4%nR4$UB9Fr zs#)pw&xQ6XpuKDnHL_hWQEL!hvXnY;am<`Td)&ju>F$R5Q6A__)k=kvC*GARTv3VZ z8Q&v8(4;Hch&|V<=lx5Ot4sgIGJs=7A14!-QWaX1bX%}2{QpXCsG1h&@5RoRPj6Yl zHowPn6b*w7mIDy0F5AgDV&umf49GSmp{7kVc$slMpiHcdW^$7 zd3d3FNYMCO2!HvR|+z_B zArxu}%B0NXlKD_b4Y^4QR8n-35|s@Qo9=0!}EF})> zH$wIMs6vQca-bMh81z6=sc@{4vAjr0QKpnvCM7Ey7Tk2B(!trVV8J()-b-|nCziE@ z_>+>6;;f6ZQi}z@E%*b$J%R@W4+$O??1zTJ@VrQpI92dlf;S0LsTSSW3;tAaub?@X z|7S7(L$E*EG{c#5_+!O9L9kkIkzkA9PXwP7d`2)Xn2t_CrCX4fN6~zhU(8wl^7xMzaCc(P|)wy!edtA(i1^+78 z&&Uu8o+~(6aG~H*!G{ESuAAw6T+qlS9ujjVIu5$$2%alQS;X`_=yMSB&jddb9E1** z;f4r)O>mSTb(7G2li&k_N>3>4m7Y-GL9y=;{IlSDf&)Yraj@Xog6A6I%S^%B z1*3v@3I3bl?}<4c&r@Q4i-<;?h5?Us1`1LZlIDQmm4ep_ZWeq-@DGBWf=2|YkCk+W zW4DV~AUHvArr-^Nw+TKh*dh3yAot)%$1nIT!6w1)3GNnrL-0+({}LRE&YE=Y0kVB= z7V|#A+cAM)``iGezn=)!W3s{axg1FQR>AKH?iM^K_?qBg=v<)xVS?ufjuV_AxJqz? z;QfNT1z!{NVco9i362&VFL;mOBZ4~xUl2SOOaz9%L~w@SQo%a~e<=7X!A}KGJzaQn&3?fW!SRBZ3I376P#iHLNT3swP{-i1V@cLnX? zpL&Xk?L_#0neOoS8WH}Eiu*g_{(;~pbcesbm^9Ph89>q@^NHve94S~x1pP9>D+T8O zNvDPgI=9gt;kOFz6g(pM6|`Nt&m@B0HG{6{o?+pxc^M-e<`?K z+}p){0W^g}UwBeMNm4(_$@JA;e32IM{sQ`HE%d>Bg6e-h)`A$UTo3h=tbS`VY{2{2 zM$oKvaIUx0w9(&2*s3;5!OYkT6K;*%L=d*0mLWyB1GLmThqzI4EyLl~d4k^lv$y)! z(2L$V1&x;esoQ!nmud0hj01+qkL@o@)`q zTl9qsPzhW8ektkKZG83^g5rd*^emaHSpq;-R&9iF1We* z(Xyxb@mpXSFMH85AvVBPe9D-oWNSs|9&susH;bF{Q zb$%gT$8vz*P|0*C;{6aAP$e|kyG0eyWE9Zvk$LDV6_2G(!JS~3u83R5T;*b4z)bsE zc%23a)OGg-lQO3}T}lUg?cM6jwp%|)m684IjyEXWUm4BKk8@LW6==i?Mj_cOG?o(Y z3Uku7u;`qdtgDLO)!Rh4R_x+ld%&s~dY0E##metpWV*ndMOJLU)L4G;n<%!ONUWDv z-05qtodRAT7t~)Ynmf2;WYgu2?}YK`Jw52#LF&~+!{a@Kgz2zHWl}<4~q3iY1G8Hw{wH#oGB%uzp0%&$gUq`6&@^n1%X!Jn^s~g zp?aWv)6M9Ydwx@hgO*g_n@%v_bg|dedTb#-i4v7fKE;A@ec#+Wk&1@6)e(DuEmhTf zTh;RLO-OwfYQC=G17+!jfk;rY zxm+ELI4ljP5M**Pc*k9K#&U>sL@t0eL`yU)zXDbALFAcI|7!ELVrFzs=8QRJdmv9M zZRJIL8(ElhE$Y~|@ycCoD7#gvE6kY)BQ1~4oCIrT%htx(&Aaos8^lJ4EPEnXc4Ey7 zbqzGA{xB*Z3*@5K`5CyLF+Rz|ng;0Di!4;faKOf2)3I-StZ#8=e0bzpY_O>BjCABU zr{OleBIg!tdPNE;TvhH5QwV41vqpd03C2~9&+4Q^P6D&S{|_|ZZH+}Vb3HE(P+qysE=Co4ngyk+sdfe0#KS-~P_ zuQ?0j63diQJVYw^sG1ETH9`cQSs|*Cni@n<5BEk?(TCv|W4;A!Rxe?iA0N< zR;=F5DGDznOhAo8_v+o7#kflvP31d~V|i!hjEXuqcxKgM4(Cy-2BJ@>tuT8CdI!%I zI?8rxwkgJ}#MxA>j0V$#)@;za0N!V5%~M#!d7=-H*36UADtrZ-FNGf_#vqL&cHkSZ z%s;A*dJ;a^KvKT$N?4%yb7$1e$D7(Ki>@b8a}>pussOeL8D=SbPCuFdyu?^&kI>`2 z?ml$GkKfLQ4>^lY8MN_Ex+shYW8xUjY$Pi;Qo)<5X|g)(H^{g;==y`qb8qoL?Rc6najfXj4@ z=UEMT^B328@-WR_Seu7yDz)qUCCeArj`HXW?~dG*T| za(fD!Rb``=)i3xKv+}RsV}hQE)SlA6U>oU#Iw$T2FUdUY!}(yj)nk>g7krHlQ~`Qr z$H~vg9`zhCW0X?QVHYi0&>x?X_|d=HUoIWwp&Oq7exyH|20WzqBmJuW(~ZAN1;PGM z&l>QpOkA|!JAdW)(Z6}t!k_ywZq=|f?{ud>Lz`yf1~yGH5467@{uc5@9^;RQ;z~ZR z4}{JRSTcGPrAiyinkz9=CV2H!!f_d2Eb6GF*RlUqrz0C7_ znQ!Q2_Lv3v0w|PFDu%J?F&cXwV?5V4&c{~C^^FU#Q38d-u3Ns6_mU+q4Qt>9W$Ico z^`@>Wlk3BdQ&H@B6d#p51fvW14`Q}Zk!U|ykUF+#=I}r?I(_TK+${KWL8Fhs=wBF$ z3deAx1&t2hd1Ag*uvu_}AaBcNxc!2!2^yWe?Az%+L+}MeuvTbW~!aBe#=gH0VEz`};&xdZX)> zI%|2S*=iu^JxwzjhS`hALW5!W4j|qCLPW!QTkw6sZgIEJ*y-;SAnz_Zl?Wc6U+l*a z5x!XP>w;H`dxhXEAj4lrMEDlkBiuT{y9Bw1L4S`B;ZN;hz~Ar0eU~8hFwoy?G$Vce z(dLNNMEIXC_)WnZ#r@lYO+bcULqt4xihVososLdoLEXZJ+T}^sR$h{~HTJ~1cZ0z% zu6wr}aq$VN|0mYHyZSB85ixr`K-jL?QCd13lhDJo)G9qOF*{0Ai{d9?qPYzw%swBZ zhLgGLaHg;HpP7cU#cD@ARMSV1g!-Xa-k49L}FMAfZaV0N78{^YjxbZ;qYUA=3@E1)u5$FzH zHy}7zN(TV>ys*mn8&bvyTCYK`74K;8lMfS01)RC(JKstA@@?FS+o50`EjzVauhm-* zZt<&-R6OSUsS3!YM?Agakk_wxTRd(GMIF3}tmO^#@~QOVFmy>DW>jZyT`5Ws;@IO< zu6^tN8{G!Vss$b#tJA6Mv^0lD@d~*%mO~JJEYeh&M;1WP`|QJzp~@tt#%$k>hfb}a?LbJGg=wda!VIQ}_g()NRH>f4uspJB!4{p z*d9#IEc(@gqCS4P=>el{Kp zBLyn3co;}~mf;L)ePH2MzymFknlRLQ9lknXnPQfc&SCL(6i7NO-5IJLJ;XG0tNvui z;dFTYBg{^AhCRg37p=k?n!`u(Z`3OikD6wYR$B3@KVm@7_)JzyiL2edT03 ztp^*IILxTB1K$Ug(=i@OquGvgX6q}B1&*RIu|z4iw3Q+9W8HB$>T4xz)MzQ+sUEw( zGkl^w+!-QNL!f%>H|G2ij@LVxZdp}ou%8M9&Ry+vP@U+j^V$H zTeDq^yHwqC^(;;0lAmFD@PhJVeN*Mf4}v;X=H%Xi!db4$PubxzMV6lmfWj(*KU*0h zzka9`2A)6y3l$fBq4?`#8S%694O7lQizM~FhK)~Ko&g3ctiTWvmlhbrCGqcItDp^) zODU?Tu{Xq0Y(Odc)_xzJquILSLVR&+aH>DAR`C4Cq2R-7j7fjeF5_-myw{*!Z%fPU? zammdKYdw(OtzUlQ;$;P%iBl$3l+99-y<-)(M*aU^sh0DEJd#D28=EIfUV8IL>e(DH zTGA^=Vhca^TIYxvPU_j}qD2e(<1-RJ`ZxX_gTE;gQhag>;aIZu}V@ ziLrmRSG@GYXBvLyoo4#`BD@dEJXJA(Jcb4l9YFHo{__D?a;nb0g85|`GC3x%c=hmp zEjDxW7<$HR&~5)^cptK4P-RVC2lL9Z<&S2jk?CVPX+9g6?J~1rn0(Ov0+@4M?i@z* zT;?LY`(0*sM)@vt2=DBxO?+i|=QlRy%kfT{#?0?Un#Mc}@1$wW)p!rN%nR^d<}%|o z`Fs)H%njn3ZGgO(a5A(mr${gJ?Y+$FdzsCGaDk^`(alT3V6X5pCurovb?o4=EI{u8 zHcNQvyz9YdSxVDbh@D;p2F%4^z!Z5Xh6)+hfTsb9cnduZqbZ1ro`zzmko>0*DtaMG zq4GW`wfNL;-@LI=Nt=S?%_q3{{cTjNG!)`Tf@h!-(>zLWwxHp&EEV&21Ub{9|Cr#L zf<9Do+Mh1?H9^CFF?S|iBlbM1MgNBXvPR6C1Um%dg657SUcX9xfqfB{;m;8?dNMB- z^K8NE1?vTG61-XPSAtzY-g*AIn9UtY{e=&6f#4XyO9W>KUN6`v_=wB1OMS?4Uyd(Zmnvss53T_kJDR@xu&w?Kaek#b0iQ)SRo-KHeptqzkFodb??I%l$J~)bnV9jJt!>zKD~){ZH%Ph1-obPF*~6U`!+B0H->w`6mGi@_ z=3SYWFaHaqIVhO}DGg_Qfer09H(7;m7w@r0VxgYtTYnb_aJCpN{W;atr}UCk`z@!0 zYayrLW2gLM3!VyW_T*fx2ciYP<*ThHfVt;8-u&XHZLh!S68I~Ek35{K3P!z$ocw6^ z156(j0F5{b%lxR-u4Nl0#`2qYS~#2tP5zK>h)-_DWe8SD*q<3$t2=2?BmN7v`El#-Sn286EYBnNlYPJN>F_@#o--LqEPgI>Aa&sM*jqf;s=r5$ zD&3kw-X2tCkFl?`oTXXLHG$%;rg2DA0ccb+#gA=p(o&j8f+LPX2?^W-P(U&nSQLX1 z8_GKMxml4HNYA+;=q$}Heh2)ZtfpclR+AeEa*$aVY9_dl3WD0M5ywbxa;)H0A%t?w zii6ZkD2Xa(d5$wRgpxQ1zN(|yPi&a%oDYhnDtGPHF@DVUvSXvzCS1-G6+-LZPfwBUjSXQjvfWXF+o1P>th0)NUvM10ePT?7PSqAAQGz?Mz9CtM^&+8|I7 zD>xh3t(+Vy8^*P8si{$3sMYkXtHN9yQB^q&nNC$czR^fTUM=-0jmw`(e<}8K0VvY+ z$*~)yK4DAuRgkN4Zt|j7y+}0HC z%YfV)ehDo%lOLz42qf_>ex~aqK8ABX1fy6RRd&D#h-aAEm>oZhHId;We{9~J!zJRb zc*n6fjou8_M^rbh3=b7TH~@yb3PB%-g0dPscuL{^ihBTuVX&ARAVLcc|S&yT6%KZq2BAz1-J&^&dO zWltkJvB*Bdxw^oaZWSMDIv2%L8ue~KdtkES6iKVc(f;zMAdl9U_5TpWM_vP!B4@VO zxh{Y(h44`tEx)@bpM|0`XuXtd3&zU-hTs?K;Af-$LXn0uGs{_4RQ!I^SR^5vB+z6? zWZSt+uaky5qUzCY=oAEW3i^@6`|-0QhgDYT@qd0V!vFXp1kSH9-xym<_t^ zzsx$yln;^XATEFTZp62f%_1w=OBeGM{Ab3V*@$RyVrG;_WCAj~g{ zSx;E7L5r!sSwnEf->?)D88zdtU2fi%H<-7E+9mUEQ1?G@F0=`>h|deoMf^1Hl)1Y( zkHrF}y_w4o7xUYK3l=ZDrJ*)8drHooP9ncucv101Uv%yil#lz*=T4c02hpumXi;8U zkNC53nH)>Ga9_#nBK9Qcx+-mT;kvD+Hcj6|?~&^a1)tkBH&U!V$67xU!{8RyFm^cT zPoaPrLb|1K4@5F~>mNACN8+k+NoVS7VTILlsOm~UMvkZ>Tb=8m$Xc1M!$oBG!aB95 zpjnHE57FrThh$vX@PK7rY(OeH)~;l9tMR!s^Xws}lYKrmnshqL{#iP?%XM5janBrC zc+OSO>Z#It6{JD8GOfB(HDjU5h+{pV%Ld2q5pNol<6>a)`k@OFg@lC1M!+Tya;w>X zo%(oM*AW(2j~qMz^1X6^%@AA-3L@nv&q4SaN&QS*yr@eV5}@<-3?L7>CMRL1Nb4LV zA`*|NGz@2f`-nZe`0(c4nR=YQq^4_#8L3pjy8Rd)=3vd~Bgil>0#!p`PAj3;mI2WFFGx6TlBuG5PeSXWT;Y zVczMP{=UfALLS5y8C!NE;ccMHv19;#%m>S+_t?^cav`tEJnl3ZJEGhE%Zx3b$D;!~ zpa+kRV+Wf7)6KES{hVm*`KoweUEtW_kq#V}lFw_b<>fL&o|IlBVm};NR41=wr8pL_ zk0mm0B4w0_7Yoi1yiTx5@Oy&)NAOX>or2E^z9X21+w*?;) z+$FeIFd_J{U>eGT@th_2H9@e}YUkIVU~Iz(Ru~8b)PD?Sc)utJj=-2PqrWg;pj19| z5P2nE;6!&PuYM~AH|%U!NGP^2{z}t!B~O7JCkj$v^CpY1O&{0M3M>&Ihn6CByjJZ^ zVIyiUgUhX}+x5{MeY6RZ7j1Ogst@pNRw5IS=GYEPNM1Ziw{7Y;4@d_<8iE^tq???Y z(h?#fF9N|0jvS!*2ti~*WLLUHi%P83au;$VM2nJzK(-=g&kszn9wrMdE*^J-nuh3K}oB?uGgw0wALyKFKq=U{X5?BG5 z5r}(ZP7ub*xW2v2Uk7X6I!&<*Pt)1R{#v{=w^`k=Yo{ZRI@H3VWOU@%Z|MufSvDo# z@+QNbhj6Q4*E1Y8dy!fCW$Y`p7NOuCW?VZmVb5E_J->EjR)iD%U*>!YG4EEX4COo1e0P z1(}Q}@^ehL>RR9St-Bdsn#yOWBD}$)woFl0jk8_brdou-tr`l6|0`3qUDfN=yFY`0 zW3>`;#}sEp^Df>kS%>lo;9J#Vu^4bN?Y-Qi*2+trV0uQ2%0dZ!)cDq`;?h+-TJQ^0 zqEc{Pg1ygHm1B|!UO_rCz6z1@CX7p3yBizZsbQ=e#8orMCGl-=cQU~jtM*qnQHknf zumIg6_~I+RBbz|9pd(tkH=28YGDC~_HC*AMbc0sOwa|Gz3u%EVVDY2-TK|FRM}nuPHo$u|%BK0L z%wxY#?KbbSKOM2N_+xCNR^h8xBT-CeZPQ#Nx(x=TX*(dA``u`8XS}bHq*$x!WbA6A zQhFAu2~=x~hPm7Wm^fF$#D-vdH#n!UDWrkl(!3`V2`Gl*!N}wIEY(uEfACQgFI`>5 zXv*)goS|@A;goJ_?Y4{UPkb#$G08{n3oj zceL(Xz6Uj1HJHJP^LgySG@nGSHmT}kozdFX)DAZmSKNA4m6YxUW7nvXf>J>4b0GdU zc!_3ja*X!lIIfM@t}+L`T@Vk0ppp_n+24_X0;>HGfTEsesM4bP`))#*e%Txp| zmv0SA_B$$(xrd_Jx8p|Y^w=0!tpPzW&mRwsngCrf=TLB_BT*=FL~Gc1P9UV<<upr|*{CF`R@BlhEy*P$)0XnxZR+97`brR9z-3D~ld@fp#@Wx?;peSm_hF^;YWz_A5OUQB#rW{ES(SseNKuMoy|Rh2U`dgO65v5z{KXM(a0N&T=lLS0Gijc5r~b(vx@^r)y3s zuQ9E>Y(n|}f8{l5xNwmtOR)DEkN33&;6|^g;A+*72|P#4!gldI=%NLu1r{=a#rnf|`WTJQ+`RWX1(h6WM+Tk`oU z7J!ez#Hl&UgM9+akjXJ+f>+POC_k2!c?>;cHt4qhGHXFYhj^m3Tu=9YD&4fJQRR}R z)`i9o^O0)|K$7B5bS8odPNvg=qcr*z_68XC4iL0RDf;8XG;LJ^ zrRZIb(zI5~y^FxRNVJFyITkZyX(f*81X z!+chC>1*|>O|RjM_`B}ZL6ajoXs#jX@e1Kq(S&Xu`EV`ukR7$g+p1;X^>Pl8`4Jhi zlg~ISv6R7}gMeJKA(aKR#Tp9Jrg{+I2q>#AEPXho=EOi&UsLFpa_{J5K~OECM2wwV zm>Z3-dnJffAh^;K0ncR!6atx$CSFD|*nLBETzMgOBk+#IDoOZldiAH*VxU{6z4;NM zfv?p#bkChHa2r7=9~2<)UV%d4)81!_e!+oe+5drZ2;aK5Q9B(d?ybc9a9}+>T6bXV z>UJ)6svq~**IL~^XDscbxsQ_oa`+%k*+VgF(_gN{8oK=FcvoLIcWCP?O%KDQzGCib zdsqWQor&~r#7o>d6eCkaohzRdS0b3c)?cDKF>0wf0A)iAGXo0J3*gb#+IH9aSHXbG zJmOkhmIsb2A%$sWYze`^)*^`DuVTj0hRKwYS=ZAB+#Ffy&%*ozbAT)iaM`|=B19PP z6F|V^%)-}lCM;2SDT(gGn0Oq-oahkeE-lZYy*fHK{5IZAm)iqtKmk;PNlA8g99wc| zi#i3D05VK9*P0!T2~QoUboWu=hVVZQh7Uq=hp901PtP*jf%j7xX&LH?J31)Y5W#sr zC~V2YKNVFPbIw^;EccL1xOkzej_#ovc*AWkUVVoqyh%}EKBgvq$Ygt;N_gVqYrP2} zF&*iX2NS3_#0olNV~b#j5201Zo1Bj$X$5*`I+lsTLady>BHiaAG#mq*zH6$eq3*)| z?@WFH$u)^n*SwAZ(_BpN<4Qj_=AFqXFx`I*(TIlcNz41E2se*o!qa>$^DL4L!C(^0 zBqRO#J-$LU`d>`HbOH~niEM6{F0z(A=%dZ40?d!2xjfn50R0m23^M7lJe|q=NgHiz zfL%Gj0+DJh=nI_`x~bSf=Qo(nQLeqr?ik4n3~C+KxNK`(T{#k@wJl>xN&PXKU_p`c z2Z7WC{20)E(TK5UN9wk3gLy_B+a`K|4nTV!(&keEGOq*ao!C=i-5IOeq&{d6S7$Y1 z-uI9K#t=*IR$T=sY=#jTK79fdqqivOY$r2gpbD$+Yqh=iz@Y`+M&`i(gLrX<&>gbw zcJ4i{tSW^EdfrZ@1v-l+%le3vPCfe`o?f62UL5iykh#&B*Ia`cbt(<1+d~e+6ZI(^ z1@cnEcYz|DPoLeY7u3S}2ViFZqIop>dNe1PM&bPT?XlHxwTG}S`PRph63}{o-x)@G zBx#KzvB_5L7gej=$-NVD<~O4zlwp0KI|WSi?d)~Vuo`$a=Y^odBI-Sz*Ss~J>5L_{ z$t5~UWr*CDsG|h7<}o?eX;P%c*6GW6w5QC;v4=Xo@wU%VQQMVK&#@;^$ts;QC)#Hw zBd)N$_a~OH{taX0_=p-$^6azQjjVnJES-T29!w{_ZotsXB2IBn zM6<$nSgQS^&ciX)wW}tzd^{45ONTnxNyUarGnv60Im5HOzEaaoz_ zrZn`ET-}}rMb%tu=Jq!dL8xwMq7BjDX%Ksl^^Fft%mS5oM~X%movzhC+0!nk#+}Av z+f!b^fGcb(JZM{k?8-spq=n`6*u6-Ne^rskXa5SzBlB_f+$8GFa?-${S&Ndu0Gt~F z&lIYBe68!~Rc=sZS}n@hpit5~cp@hdJ5`G1HwdUYz@u2`g4q-6pX~5_Eti7`EUEfQ zSHcabv=IFFwN#=*L$bVE>JT1@&2jpo_GnMvwTINwHVu`YZPm%%;e>bK*i|MCNS!^_ z%Qy5>J8&K44!tvMD?JQxOb?KtHuj*{m`sgi%ZKP)O0sv7{eJiqwSfI0RLXZA?Rvjs zpA6ROj6)~V7misSUHcrROFpi&!5G$v=6gA~1-NoJlICZE!u}O%aO0^k*uv2s!T}a7 zd>dd!oobNS&82P9R;#N-}Dg8eK&TRt^uv%Na!q7-vG2aVK&5y`iEpi^|gKiVnQA_ zk!CTPeP&M8^@%Hrm*Iq(vI-FOzN-&<^zpU)3g-CGsP}I`=6w|bx|A@MNx37^WVvex zQ-&<|3RUd#CBROUqj@QHJD3Zz2WR2)R9hQxhO4wSXCvxW)5)~G6*#cR5>E~0?8(`^ zm>UK{de)WjqxORnG67!?V>c2R^?sn|c{*>CmLExcO*^WAJ@GruWYKqN=m}&r_dN-s zio1`m^-k?cO}!FpT_F-pFi6uuBSG`fD*m0|ZMG(PT!TWQr9oMIOEoCAG~LP)|BjAG z$-5ydlh9C5YdI0ymw5F<(;#zQh4sRAQf|J6GEd+1w%4*&lrvTf8oYaX_6KD~KU)!E>|pq^ocpm;s3a;#_Ph#4b- zdR}+Yq6Pi&8HpeL8-GXPFH8q{=*EX%5?xY~H${K{j5lTYOgZ2`n6#4)>G4;NAL*GV zU-%TpY}_~(Gw*bxKSP^l;|BE#$vn{h68Kxl7kP|7BBu7qXB7hG!2+v34|`~q3)730 zOAmSvLZ1WsO!F9e#%$1S|7Cbs{EmEBMwCxrUQLsLU6=zu|Dfmqz^e23)2#u zM!ucoXp=e!rH(%#A4YfmyQtJ@DDczJPKYA~>jb||M8#|s^A^EJ1$nCy!|fA%Uhq{x zqr3hhbVBr3CfNJD(+aV_O>mvyF9dfB?h`cUo!%Amr-DNe2je+UFeqqr;$J~C^7AdR zZxOs(@FBtfB*GtMqDb#K!B+&22>wNIHm1?^*C5y^xKglP@Q;EY0;&7^GcljiSBF1K zut=~<(CFZ=6SFzjv|Y?RuS9x(7V}$zeIYN*bY%;kDL7hig5cGH*9)!^yj?IV_*+49 zUg>o)eCHub~;~dkLK~@hw5}&S~}vo+bDd!Se(s z2wpF^Lhv@h`viX^_)9^fTR$P@4+S|`Fy20b=K-nXnfyfB&k>v}_$?ypNu!vlgN*)u zC%8xOIU@YMB4(;%rN7~V)P76zC4wQr#e&NO?-ZoUSEg&LnA-*46#P^$cc7+wp5Qpa znSw^we!ZBN3jRoNtKcrd-a7c-7W)qb`=W1UKC%S!1kV*L6}(QcR&b?Yv!E?FmGvZ# z`zVWVUbr-z+(Un`g#o&Jv3-Ct>$!tEB*?JIcflRh{lmvc}aOXQcWrrW46XyR|imz_|G{bK9wb-y} z{xm&YdqsG9#w5xx+m;`cgU%G}NUwem&Z`{DZ!{CoA&XA5>T8$xwW8C~N~UJo_zH;e zerRKn%L93QM-z-^XW(MOV=vhs+B-6)VlfOO)`b4dxV1B$JLuSNld`w09d`izVP`!?uPnWxBkq)Y}dPd?u{ez5p z=+C&(!n_CY?k3Tjo^cDEz~2{{|6T_Imm{os3_T)--Q>f2Vm82pE>)$Q>0{Z@Z1R9t z&t4eNH67Y|3%lQ9;V}q$mg161HY}7&y`MK0cJ-5J?Bxq0_a^tnjkz~ zaH}9L6`JSjHa_<}YjN=xKa;VMl?jjOHwLMdhPLB>eSR{ROi^cb4Kjfvt&kN0v$oN< zj+bkY1?1cng3A`pqa8S_c%J1_`lzTm~VOugcKc2le@+YL~7O%eB zw&a$Arb?cd)dd#5n|!y5Xzt&bf0jPQuvYiTzpwQ|v^4CcX+A4-JClQ%J5=egRym(r z5c#PyC)Xq|)D-A^r+0q!#gFBWdnU^zyG-9LAxR&Zn&!rMt)OCUrWCk^ImGsxG2m-fIkNwc`X
kg4heK- z>*8zPomVoqpy}e|{&1>%sd1ejM%!3}9B{Oaqi?(;>hS#@=}r6j!O}cx2#Ro-?;c){@Byz=r8nFLoJx9$9Ff_69$ZZQtG?TV z1G^KDYMij8h$qftF~zZh98y$C9v5P3`03x#`VqnZ=!vzu0Q82{{coRqEE= zWOjGXxZ8dw1c&9;NIyf zAT_EJsnv@}UOwB8+kFkpbZ7gaTDfZ77}$Q$N-K~Fv>()2GO+2FOm5YzP+|~zX91e_ zV=61#4?4gr;2v-WP>`VKyiV#{8R{F!+q}{`FZP&qcUn50J*m*O_GnftNQO$Lp`q$tb+0owOE=__xq+r@;2O{^ z%o*M*y{cOB@{FkWDHH)KeCddesI`Y8qZkxG7c;{NaqxLnlcPwOQ9^E|}b z-TZMn76>_=@Az8kGGSbS+Yx*%6R}=!29mo5nVlADU7`GAq+pq#}|k^Ofem`3wIck zRV`M6Jvb#)!<{qbMBT)C&yr3kTUC}f!WOdS+~5qvZfbN_6P@|wx(CH<+6^iIff77)DR1e~`=Xh^NPtYCz@N z?((%f;quQU!#{?~xb*=hVGI-VzAKeqtteU1b<)<|h@CL^XyjW@2BxcjP4!10SrpCQ zb)xj1=ZZf^$8XYGcB1rB8KlXdq!+?cR8jz0n3(td=uJ{hVmiII1bU=*PR__VnHh7k zN6ztLp{!@2>rP`GSCdq-BWF0%GUa9%Rp5t${^s47JqCG2wXTazOI7<$&Nt1zyZS7B z@pVGB%0x7`FJyZ9>kUCu`}^q6-r44B>5u5}Ma;(R)69Qo$EUb5{45?#z8V*rsNQ*Q zF!DWjQKQDQe@WE`l&`7^h`J1O792kQXHkb|B_myazC;IluJ{6xA94+!t7I)q{X>sC zmQ@M8B4$|-7l{P}m|5Yt4Cd^|c5Hxr`u3h@b|E&=BSgrAz(j0xA{P~?m;a7LKU!`( z7tx?CCi1vL`k|b8hWRk0>D}gvUgj*Aoq?=J&RDgPuSF2FF4ch{*xO^v_+K>wdl;8a zx+6kR+c3b;|K)HUAj(4SXE z+K#6>cTDcs*SSv*C3@_Fbc2e!bAPN)9w^YvxH|W%kr;2XL9PW#BH!;Z_$*D<$JBa} z%Nf-xWp=X8?3ZpIpLwT#L z$gmZ@RDZWT=1S#NcW?;%kIrYi-j6-gwXgH(t{v*23_cYb5I-3^*u)!M05Y50)rvbQD({SP00fcn*e^_53K)L?Ty5FTJ7^K#s)_w5m z!7)U8Y&l*spqL0J5uvL_y76n+>pNpGAM&d8J3Yaw78->Cby4phM!XwWT8nUcDdx?H z=@zf%EE9CY2hE1qDfSQ*6gr&brng_1&VfZKsv^R-ihxAepDinPunv6df*eRW_omXZ zRN?s6)j$%%-jS?d53$&gFD!y~8XXSyE<-#=e=Zas6iVrGdoD3t$$A`n6J4|YQHN_f zh$y=gZ$au}dL4+WZBX_wrK|T8p_OaFm}`)zQhoPNvN_@oAxr^$>o*{1s=iOu>-V7U z^Bl8&52}$+%eO^dNK`8!kC}BLL}+8Gnw852LJV@$UFs z`~p39P8@`o2fuTCVq;1CwK2a(o`>MqiIBt7%z|#`;Tix9sbtK+A<_fR*hhEfzJZP3`CC9)I24X%Khy}jZ zai}L)6;xufcqZCk-iNE!ph@HCr4J6cVD6wjtcD+2iv~hbm6FLTxeAKrWPBGXy*~5? z%`2Tp#w+3Sp!ON-55IBT5E*$H90_|E>r2UX`AuU|?SWRvK+u6sxYL~6+e2GuqjxJx zCPPUdR*vOy3;MvQO+^v7s-S6Pr_z3c@mJA=4i#o%Vmw{P(Xp@Ox&jsNt0-`&)@m*W zLx5An<1+;=lBODHD#q+kXi8*y#dv^9@wVeu_yoNdk3e^ulQHXm5mvlyvS==cqv3Vl16M&;9jrPC13vnp)+i) zs}a60kWUD|(lhv`pDe-Ndt{rjxNN`%kr(c$E^1FJ6L^l8v6xoR3KuO}SlaqHnX^^! zS1)b^(&7`qkMu{=fQSC(=~wkX5C7>N5;Xpfz@JG2oRlB>nL?%ZPh;%$F%MnpsRt zpK)hBq@6LJi}yU2`2xJ>yUhH~tQ*FE5#IST=C9*D07e?eh91 z5MpbfX^f{~DNI4nGK#P*!!=G9DcLnhur(}&1luC$;)bMJfRbv3o_V#k^Xeh4HrjLJ z!f@S^T8gkK-QGdED}CIH7B33JiaWUTmVfj5@KSl3uix~|X~*4-2H)2&TQIMFA+uC~ zANPA%H;Cf}`MqgY?Ho8?%r_8+cvSh)oeLAFmqSBrgE z(8$k4#r*GrF9;qId|z+?Xp{a3!5am6Uoz#%lpGx1sWzAXJ{25=RV>Xx!3{v>Zx<2y zdq(Wv7tFvwME~arP7wTt;7Y-@MC9*>Vtz*O4MBB38|Y;96MBM1o^7g_7Yg$JHpY9i z;BA7N1n(F8iJ;NT{aZ0VBlxOd1{yZ$og%2@+h86o=1RdDL9+Pi|2DxN3GNsCgWwUt z_XST!2hVVq2u>9IhTsChn*}3+-xs`3aEsvMg6iHk&^;*T*9G4c{JUTpI(n5)!5qPn zf`x)t2v!JQEyz=_D&K+|1@9I755b=a{z`DK;46Yh1V0rt@_DB~n1uAdCOA%TqTp=7 z`GOHaNAO<3rv(2X_?qB<3HHTAi18SCJszZ@xl-`Ef}aR>3-%eP{S6QtEO>_CFu|`0 zju4zLSSPqjaIN4*!5<3l5qwk7$l;}l{M@O67YSY?xIl0*5$&y!c)G`PyV$Q6{J!9Q zf{zj5@0ViUA-G@gfZ$7luL-^{mv(Ab42tJ;BcePd!!gEqERg zLPG^a%p*#Hl;gdOn1{I*?UCO3f?>f;M1*^Qh;aV_WVl}t5pFx}5$>Si>w>umL;Ldt z#|usqyixEwf~`b+pYMtJr-B)XlXO-K-Y&R7@P~qr2>x2|Il&`>9|-yo2kD(j#P6$O z9xXUquv&1T;8G%fw~2Y9;8ww%f(HeU3i3`(#+NO4rr;>S@q$+fen)V%;5~v53;s;- z3BiMc9|(RXcoEh|j2BDPh6OG`IwOBO<|Mj}FAfxbVco`SQP=nc)&G3xkVfb0dW;+$ zxNc6s9@_{fFf=M1NXUix4oQu|wsuUI@LumPf)3=(N;et!WkDNEj=uW9w_+gLvn(o> zQ?~(Xl@fA>Z6=r@4WLjmvj99c>Q;OVrY)RbZVB;U0RNh%X+9!7LKdZsVBLcaKd7w` z*%U~|Xyx{lG+=1G+Xxl(6Ch=vqKHjmEL4>LxN{{KV=CG!15GmxUrzbzL0=e+h=ydD z6ghYs_SeU)zA4h`AbiP8Y+F>oQ)C-d#G8B-H7x-PCg7wgcKa{k?2&WtJ>v7;WA7aa zhCFhGB(yLpt8Xu{31}TumMmc&zJ?mNR1%oGBIfSLddEVixASORr43t4ki_Wx6q`NR z;OW@W@d?ySeA)#KTJapsv+w*=DK75V+3_hP$ha9hi>8q-k=6DYQwxyLZMXSE1zfRiP}T z36ui4n}QP+=X4`IA$u^&yV6c~PKgFHoB!Lgclug*Ik#+SJp)A}F>07&xR#Z0z^+y@ zqb&l86qx`gxD7MZUUDv!kn79R ziJh(FD#AI@(*7Ca*imGRV;9lfo#|`gmC$<6h$Rr49im@UrGH?Ff;Y>;jB01FbF~FMOV7}9 z7L^Yna4jlTg;T`i3}+(10TSM-PK?`M=LH*}MAaD3S`U>)YyC00SCPse`IcoDYDz|0 z0-H8BfC)b0Q1hp!_|`?~2NI9%87O^^lB;a*(|}hL6MK(PJRJ!ujipVAtBu=RzX3Hh z?2e%IpbOoT*;nt}ulEk)L$&acK9`U3I|@2o`^ZM{eD*6$a&gR^mmYQ}sy%AQ2pRg&7%XD?iOYx@K%Z`qCW+9zbz*XJ#3pWqEI zZ15y%831{aSlct0hxUG#hZinwzs#B!UbLkBvdqPK^^4js^WL~9>`9Da0G-6&h2ZzI zU!kw@eDH7AJ8GBzdVF`*vah3jD>90jyDeV}^_iJME{6DJ2LdRkaH-@Gt%3E1N&ev9 zP=e^1KqV9#uB-XRU911Z&Z2o2uU;v)&rbX&_Zm>8bO!N;gXI3kRSo@C!9&%mrTtb> zZ|rV_nN5Mst$3M^2#9nbQi#>q(_=CKwd-t@08A@Is@`Jo3JPLt zy4(Fv!eS1*KTPlV77qd`NJ^ZIbP(s%u|MWoo-Mmt_GGm{Z5-lI%0ZV&3_2Tevncfl z={VwjV*?o)8E=5}DcsTeA^0BSzRQQL2je-m3a_;X*vhXxHX9*)>ozl-Yi81PwKI;j zOLFOC|Bg5EXw}nETp`L&w-)X(?_jO8N%tjj&t(X)K{=dmD+*e|qU1XTBGd3=q^dFA zPqLzQJH!S^@P2xX>Dbq`FE*e%HrQFd=py6V? zwa>8Uvb)&Jys%F|Pk>eoZ_m&sKs}r&XZu#mE=0d~fR?z{3zGn;lFn)NEtW%h>I%>r z4pORHXwiK_vF?r_DvIV(X_wf8(I+L&p?r|)3fOKEr^BeX>(C^Nsg?(de%k58PlXO0 z9pJjZpgB+)Uuvh^E{y0{YgkKJYgp+X1kOg{h!j^Q&Zw)x|GFCdbJZHHel*?>fsVpO zZwAH&iD-gWu@{Gar9f;TgR{28206D_g}8aB^+PR)A{Tt!ikHr=jhd8k5$e#-v|{Oz0YuezF>)bvL2Xq3Y<06Z4r0r|W#o z7xTI63%(adYTbkCdV-NwZo|M>xC`$?YM2Ac<)npgrZZ*)L`EVa;dLd6PZGb|Zj z>wn;Db?#CVq<~UAjFgmPOmFXp&jxp%oY9-joL_dmhRGS0Q>c(>h@dn!qGNyO4*d3Y zsDkWDpyTJXNj1T)Pf!c0;=Jgo3W|KSET6 z|8e&%;8B&=+6mb}3Ih}BAi*=pv>iP`1`Rlo3>h>)fS^$WgiAeXMF92w$xHfRf_GQN-L$_n?y~v37T17?q-*!1N@bT^RZ#M#pkQ>_`xnjS1=**Sf|x!n3Jm{uNG1sBJ7 zD%UmGr~X7vB(fI?i_tvVVJ)2O&D!YPllb=zN;)b{^uj{;r9*EgM#-=!&y1w*mO0OO zJ+dAtV%vXUH-3)YgQdJoO2Q3zma? zlX?88@D=@6*#^ zFdU}Eq`^x(hv;MXU{Psi)O;u~qoy7ZmY>vNaJrc6if@cN4{(A%b`O@XUIu=``FVT+ z44k3}e{p>SlE5)m%@yCaEQ0OvK4Vu30Z-Gd)N^1-0q0kl02C9b=t#Z&PWl06IM4iM zUIl_o2yY)PylnZR%NNxys{2;xvc(HR3+gWuH3&bU0+847_T!bIB}?lT!9CoJ@WPk| znFLqX*Iu?Pbos)X%dTFuq<$GfTfS()!cb1wy;d0NT;!HdMjm630&~mI% zmS3@G;qp+I+faeVn2xT8Z(QT}OzFRDd0oid625XF5|I(yXYij@xopYhwF|GxD5ZrO z@BAfKErrd(#kfewl0#`p3PTeB=izTR{-9n}dh-wY-9s~c|8luB|Ihgc&cIoy_i>Kr z*OPx>3(k#pTmL=(Ky5}?3 z+ET?aKz_F);b$79{L&5oE>^^`qkMmWJ9cpIWBT}4jX%2g+#QBH{7-*OAO9BNkM6wh zXr?0=dUiee2k6cVn|?iaJRaKRq$*k)m zKf;ex%f3&3fuD9+OFiAyL!UkeoaMcp<5nR4_ z!Qy3Cft3JH@li20Ygx^5DvGm~EL;Ybg8F3(YcXk&u>kV87hswodjXV7ML8yG0XY^t z0XbweD9Ty_gLAUZte6CmIs667RmCJRIGa2M<`7$Mj+Ma_isvd`sMwsr~^X8pUMt0KmM87=(W!=p&ObI8YW#Gm!Dvir=I87s1P* z`n`%TD;`#SL-Ae391PA3XQ1L(#qo-jinA3jRlG{EL9tnJ9TEAxN%b2QwF#eo>q={}%HG27IK6i-(yQY=+mq_{-!Iz>;0&UaM*GsRyj zQkXcy-%UimJQ+Jrsdg+sO}zh-Z@`H#%(pTi2ws^t6(=Z-TxjlSS3jd3JUIJ_2=4{8|BK>B zirE;r7!PT5wF?)2N=D8=n*M4Y&;8!)54Pp@o2a zlFO5eTF{POOqTV|0ujsdNIPIBj$;f$m?Ug~XF0c%BoG`H9C`=jBXb9hPcY9Csq}FE zF_Qojl8{Vfh=>t7B5!riUvd~B(q2yCtY@Snf`oq@lHO%9P=*i?S-}Y+!-hXCj&(I% z^FU)L57+f>gPVS{6Sp~9KjB7@w-`7TxIPZw8R6{4y5ucGma zs_u-8V(Ka%ylKkv;eE(}+=pZ_Vq>4kEFWxu`S59)R~`DfJ@hsL$+XYuq5lBq)M+{GpE&bWRd9a58D~ktv zU+H${;TWkgloAkMx961{*E%ns4n$U%hU`Pqx~Q!npz-kx&|44VFzuzpfC5B_j`z1iI26-}abQPN6p}BQ1K&6S z1Hnp&Z*MbsxO*4^(vatSz0D=Wx_-${UfHCTAwL;k=)OB>B)8WYE<==e93(`pa7q0& zaij8le4;?S1Z7XwTouY|la!kftybcb+bSn;tY#(;gZqcH##dI6;VZeSMSJ;7>rD zxM3MWvO5n<)C-@uY)Av%q+_T(+s3xk5%i9X@yqm&3N)yBDB=aETD}um27LqiMkyLj zEuvhCR?ashdFQVH*LM!sa&^xhz-<`%PYwE0G0H27Bgu6%GB2;8M@8VX6zA!yV2VLE z4o5+d{F4wsq>`EBX#LFLDD=J^o4BY<1Qk~58MPGnezz?WGw<|G&sNY;R!QjvKX!k6Bf7= z5?0Q{LkG-VM8o`1G7H!BixE=eFXb3;vQJY}xbljm5DLxdDP-wLe9W3KlptIP0pMA1 zI1$MfUWTAV*uj_F3Sb>VY>cw+r=kS&heUa&i86oWlk8>K^<=SKNLj74{s}1!e{3rsLNcvENeu;u&9-5q4{wvz!8YA za~~c7het%73(`WLE;2o@td^05p>&1eU%+bPS;ODc`Jx*z$s@B$&^%{nAFLk+FOj5` z=TWqq7h$__vA_9pfc+i>y<_lEpK=->Nd$-Jpmi3Uz&9!=Pgw%$20HRS4TTjZHuV|_M*3&VL zI9+Yj-}WNHlDlZgZo0nLWz=`lqTr}7Vh({LD0|fUI3v(0M>i5(|%7M+6g9t zk7%WH7j15*u~6j|9Mrmmi`Qpc99V0ugVzFOkg!m@^2%k%R5!&}ptgevFn=6ib>m99 zb3Nypo>l$|tNI^R`985sSGiEsC@zVkdAhoP(9Kb1b-Ulrw#Unecr6xIr?JA#cwGis zm!!rS%yH5gz;O~|bi8FZ87wZe8ZFF+7%eJf5jF=CA;~k}vgSBLXV#2>WBVO57w+X; zXlU+u$!isCnjWm}nhrZtwPp@16@ZwhWH4-^tC#?6~QAa5f7Dvp>!-73Wm@ztfND0gaxP{wyd&5_-qic-u_f? zw6^5dS9#T9N_ukrc`z{7B2kK1adoeVx}aI5NasY*N#V3hPF<1Oi0L%hiHqT#M;=Oc zY8e#OA*)gbvyI&TnKhTP3_dW|v}>+}#-rB-=IEkQ%fP(%lKLt#E$d@x$7*;MBI_Z` z3(1y$auXEGl2<_u2iz;*C5J6QlOuEIbW>>w5GQR>$0))q!iMS{+?OAr=yR zV@3N$w<@7f2va3fR-^`i2SBT2Pr6EEB_U-nXA_qfm8M4iXo?`?vOZcR`a`8xJ>6?% z4r^t{>CA7sJXrpzm5fu?0jXvv(QPJ|VHZCxgyYH3a&Y}%KYwLi&2o7JVKmN87luv~ z$eLMIdD-IH?hb3};BeHabF<1o*$ah?r$Tr-ZTV@Vi6C>4xYyI7XdzSfufFfv^M339 z$~y{EcxbC%o+8h0ag>$*@98~GKr%|_f$mO*JE?hU@OfbnF@mSRY6O-C100|Imv>NWaeA>e?W-%i3?or`@lf-x zpdm3|tONd$=7OU$p-r$1sb_mY(xgnO9}abXhW<-Xhw$h5|97YhGW4wf!VEo>>5nv< z(a;s+&+|`pDgM0pS>I(DdaBDa^wXebU3>01;Z@?#3vVve{PXmeLOm}-e+ASv8TzZB zUYenYGX3RbVJ)5Uy@P1hQV@u~k-la+pM;*`tji$} z0CXX|j8Mq?rla8!1RmJcF1m_zpe4AO3c3%&1Sv=Y1$7BmRPkH_2|YX>T};)og$tmj z>K|V%DkN%%h><2aV`HCUMQpJlE|3mRI#TAO{ z74KBssrZ26yF@I4K2q$9dgndTbAgPvLUER2z2bKjw=3SK$or)9cTn+3#pe`9pgGh2 zEX5YZHpPvKKUKU_@hQatX#Vtnl44Nt48>(#tXaf{+^#RG~Rir#w( z@2Nh3PR;noDPE{JNAV^_k0w-zK1BB(4d`;!*C?)5yhG8W?fgdd_bWc8_*cb%(sDwI z<%)9@zoNKF@vx#t0~)Th74QD#EY<&qVx8hDVm`(Q)!(Z4Q$>%)^Qh{*dzlnS!FJVG zku)5(tBKU3Jf^DoMXHzknQ;FfYJMe+7T=6wdR|ri+ln6p8Baf~T^P?vK)M^MI9_oG`XB92M|lzP zcJ{I*-%OL9y5y|m7TD;*!cV==Fs7)mn6EQ@mUpge5Es9w{1#vxf=-d~d1sN;IE#cF zDJ;Wluy3uyUTy{U*bO+0D94FnDHw@Y!56q7*AUFJraZLd`J%GH;zY0*CxcNrv&0k2 zI9gms$GgJo3Fc8$1hmlvbQ=ICR}q9FCy_j*M_{!RKE;7 z&&}c6p^?WTe2xEsz2_V0y^%A3Zry;3U!F4sn&NrK?MEAiW3N=~#!qsFL&zAS;pK^_ z8_fe)C4K5@+^;}hCA}i|WhJ@R-2ho>ahw89Vi24LhZrcy7K3fGaR-V0k)S)miW*)}ACK927?^DMMOrdS-%?d8#+ks<2zffgafoxlb_ z=|}(xGnNA=9cekSy@vm|@q8qLf}V37K2RNDs!qlut{MrC+=e*uC!OjiAsQVmILjW- zCWR+88!{ir9FK;N7oiLA+x6~f7=`2m6SFnQoFL&%W`7GAj!AJufrj*)5Sf1p_3a38 zq3Z}ToU~3>k9eLN4tjd}CCqr`2wqWUyoZ8AO>AGin{U^MJ(Ej2@AwO37_xtK?v+P5 zg(V!`3zF7hBq={(y(u^BO#Se@j)W-d5O0;G&y2`slI#Q*^xlqlaIS`%T>73RhCwh> zKf@H&g+p%OG4CzYmK`t?>0_X=(2mriT}$+ckO!;a^>1zbN12@Jb| z$4#KU>n0#TbRB1+<@9r-=8OQPS_IFlY~NVBY^){r{pbQ-)$F)*wbW4&AA00|FzlMN zCWUibQ(XV&Bbz{uIRsmw#HFV42&zL9BOSf4ot~z8EJ5Y#$OwxDo^~YEbf4+2 zm=5%#9X}3eOrN*UW_V#*=tn#Lou{bAS;xGH)PQdIU5r0ZO+DRxmi_ZU^wPQXpr028 z5#vGn3t_ES3PUWJL|zh;!7^kyd3l9W-ooPk!u!1NJiUjR=Ksw8nd#ui^5lM)d8OLZ zp8_@0=jlUGa}4nGr$bFMPtW1C0DsIE!{dIKW}f~Ws99&8z65GcQ=T5m^!HhKASbA6 zwn^?MFG%|~>7Lm`?=4O~{Z3y!Uep_d7y8DKH4(4zVdFU(J5T7(fhk!Mv8KVsbLpjK zeM5mqix$^iL6fVNE?Zoe#f1RZM?X`1N^t-xiRQxOF$qO5Mir7Q&A3?F4hD40$MIU~9wVwm^Kvgk9k{VMn->urXXlXb$tiDa63G zi5NBj;Juu7Yr|EvTW^-L>%*1Q?UFSv;#*6XyTa9Uxg$K6cII&z1lCNujp2E;+ZtX# zyXNpJ7-F5QK zEpM6GER_fPa^fq(vNqWWxU~aef6MnVHe+pvM`7~7`Jz6sibNS9)-Edbg~nYm++np- z)o$I4<;!s=hFhbMis1~spyhdc=*k=AYSTQ9I|$ZXplt8W;hQE-Vat2|)}c_!dpa~` z83U5mBZiYl)}>hNK8Bqkmf?l%7RNGO_aa&5Ze$|(nC=K}qC1p-yT$tU*2nQjp{98x z87M|_3tY==f6NW?WMG^V?}MA~r(jtZJ#O`p^}Q_Yk6S-9YiuNJ4Z>)O-+0`=HpEyq zYDy2HY;J>9BK){lp8l3kF#2NQH}7~~^!p3HGgz|9JE(zQ84c*_C1Lz{(M z#`%O(`3w|Ec_p+}yvFx?*zp?QAAq!}QHpc+Ta`K3y3xs>VU_&?9lb`?b9`eefYf<} zsZx_$yoeNmJ&K4!TuFa_>sQe@+IyEm#}6^ib50(;8w?H2UmJk^587wx=2F_2!LcN} z@!yPdW*uqCck<51b~ex79EE#lu(+*5H;>3 z{0kxlVK9ludA4*jZzLypv0*wv21yX!tk}3EneqK z-Y@_zpp6>RK@>7~?;=734PYAD9HLo;pq=8Wb}<@5gQ2I}z6a2tD(^%0KR)sll56mG%=j51SiKW6;<_0Ct*&UTR8>QeV@=R4!2V0f4oza{l5+R6K!u$+fd z3D~*qlO&U>J&&C`-FH;m$z-aCAEZ8w3sy zWN;PK&Z(0i5TOB$Rm9!ffm>N6_pq@d6U}fjGS|F}W&3`c(OA7F2(dze8%`VS=F<`C zgFwnQpgCI`&F3IyRtTR@6ZePqz$I-A3ycwG(A8RJ*Hpp|fwB>^#j`2SL7+ZhB?4pJ zm}lwCGXrk?$8bp>tWLzjun`3#>)vRe+Z-`2wgD1-*l15(Ia}V75Q~kns&;(e)A5UJ zsa9Ld?iJ^;7d!pXzLq*NJK4Vb%tdUx4k2F6gko0bCDEH3e{oz^cd1P^%#0U_x^?gmL6ukZ_XwU zrO+OCBBDeTjPtorko}zV7v*W8^9B>bJ&MKdCS(=KjJweeT|rPNL^yFeIx2XLJV8+{ z@>B#6iQ)&ngT0EcBT8@TIntR`3a2qM+Q}&92*tn-d}3F8Vmad(7)G?%M`mq+ zw<56cQ=TPfKp|r>LQtIGjVO`1TxQjsJR$ahEtZYXo54O+htfuRZl?#cgT={kB5W!Z zHCq3BWNDt$Z-U(q*I0>1?_H?CON0mm_x!Qa9^*6TNm z2T8U`UTP@@IADGi%wjCAvu6g>kft4uhSa zwoqx8>1JA(`ZC?`;8Z!?hMqV<8>&JZ`n+z0?q?eUubXRq*sTo}m^Os% zV{W<~?UeInM7RT~bc6RZu}+k04{1q7QvKF&ZAt5;CC$*5geNrkTx=QNwUp*m$yt;w ziL+=|OTv~aI{m+EO)PFRZ^~Q=KPz;kFl|awVmEYVG^J1MK&M$MbiT2&7*Bns-;*%y z$%sjEf~}}(w5JWn>%tlB3Gbnrk;n{oGFzv94pu_sprv= zQfyl<*yu*7O>cJPzX2pk*!I;L!_kX*pwx4FA>1Og5KdK>hn6k8YRT0gi9l#aZT(e? zmq)V7W=$%ed_fm+YV_n&{9k{EX)b3la_KjZWSHH zWD7P3nN}?z$Ewp*&jkg)!x>>wPj~!!(o*QI+E~di!{W!jz(ziX8hmtjmQl(t?fB=> zQb;S{mmlbgi+aY(zY6@(z2`0jcV1jD7B%%>#vk2zUjf`@exBVT7)L7PD` zBz-JH(ptc((Tz3}hCYNp=7aWZ2Q>5aW1ud`(8r*TWa!63%{Jk=p8$0XjXm_Y_t5{MhyFJ`^d5m^ewK(p0`ntjP@{zg1tA%r zL7kliV)0cVMb$04>xWp zgV4XP`eTZp2mOWa{tZakAzx7aNX5~LV-?F3FIK!RM{1sfg$2VMq*$UjS@C?ud5VjG%(JEQ~X#lfO(JZ9L0ki ze?qt?0v>xj1-0ZXL#*%O?;Lw#y8hVWv7cG~e{RrBl3ZtSb#fy9PNnOw53kBbZj4QoNEF?Gbj-BEw&cRB z#^k;9qZuj5%LvEc_AqVMhJO#Z7ZpNR6>yCJDgo_Q9`|?cWrJZwGU7?c8!pDvzUGdQ zzlCkMD@tYqd;L;)v?D_hk|u?RuOQ>AHK_;=0vu@#DYb!`e$Tm~)imw3O8WX+7b9|% z7JY(@Y?9e{GGdglwhCWDdzs6$W&IA}^4N$OFB#V@lT86hCTqaUB-su$8%^<(LCXCi zhWC~O{+45yCcP|~gKQ+AoH+nXtU2;>pfU^{Bjb4}DQ0u3GB3cDm!VxI|Atb)3>7zC zk2+@!x4ehUFgcBbkz$%4$}&mPcc3BJM4UbEZ*E5yK^#&9ult*KQoBns>GZ|n4T-ju zF~d}WJnx`yd{AyPs;p~k5H{P=o|k$dGLpdDXg~X4(>@EiD25gZro9u-Z+e&#rS zjtnt~`a$r{gTAKt&|d!LpI|401Axky@pEl|1j$HSo~rvLPMRxY#yf;(pvmA!pl%v+ zx*iUuX^pTw`PW`gTd-Wjz-s|Z*lhstYuDE9Z!19mLwV6231w?{0^30QHRoae*0*Q^ z4(yiK>-(cf=nlLNbx3XCa@%;fF^-XTtms?UBu5EmYK9S$r*rOc> z{B86G-wYhFF{^GL_g4Ou~clvSvUC*JOS;{k? zx5ALdfLipqRoTZ8E16J|Su>vVg-x)qMO1YcA{@5umZw$>C^6jVes?|_;9AKNLcntw zVBVo4RPzpkX?V%%@QNP%tCP{Vn%bqb{H=bp0*Kl%%p?Q-ZEs*=KzXsC5V(v$(RVBqp?Jl>bc;PN_Cj@YR6|4(L$Hq% z>5Fk?tAy!qnL?kYML2;zNC(@T9r+I2Gt!phb%PL(#J|??GzGtdp2}?R`BN{nFNWG) zHcSYo2#Ckz&YAEc9o$f#M@D{t^sshDM%E$boy@V}K0$;stgSb#Q(I4@4GpDgWc0=n zZ$OC1iUhaLStW+|i=|9HA{5huF!ir}4eKHV!x7kt423FARd8s_>sm|xWSjZ@fM+&G2P!hm42+uP==dOB&!<@|5E=6 zTJ#9E20_^UZL7^W8wJHkP%gC$cdf9T*^%v9lx`pedEvVZ16yap_X5YQ9i~hSAvvqLj2HV`g4Ni%3hCL1$km1+&2;@KD>6JnD z$#~%d!okd|No*I&S2@y+a*W#%{FNDGrbfmK(cGo+nfkEf zXLGUvT~}tTN72YxBmTD67?7zcH-0DP!*Vz%M=%m5Hd>r#r1E)mBcp=sWXlJ9uTp$M&hrU6MEBaZ0j+*>M;vr-~@yyzD!582fBfL_-EX1 zbg0uShodS(bIMj9fxi>9PNwwIz#P+u&suVCUB@(F|)kI zV+@f~{jFa_L-WdRt10{jmyL_XXhscb5#S4R0s}{Y%X7p>Bf#}xCow-%jd%v5*?zc0 z*>UtlJko`%fo^rL;~<8cyHglAZ=)kKi~HMn1chQ?TlLc2ELloge?-(`9$$khh#=8m z1p^Z&oF*+i;FRzk;b_&l2lD@S<2@=cgCQjC>yKo<2hTtw2mw{Thpb<}lgeV=taHS{VJJhiUElV<>`C*oYM z#B$Tje7u2+v~U8&(p36F^WUIBMy2IPxcXv|@^9APY%~b4ZAXVk73i8fOiIq-g}|f?}CNk z?X5*xN||`GZ^0sSsZ(8qypCmF`IIf%+V7d>^}2_;SxW^C7X8ZPhQ(vnunfx%{uZ8S zWk(Czt+SwD1CVjfFnF(=BUxQTHTLkp*?psqhhAQINK8~6o-ajlbu zFSjKJDKoF?OkzGwu#Ha$(@E_}ES*8{lbvwQ9soA zTkj@o(N>dKGfDf~Msm?_1}Mk6!`{2+WxgH4WVKs3oRHkHQ|n3uNj9DKBqV~%lpLhm zH>A9U;wWpeCY6|4dLa?^zW1Mob1uqqPK8422vsx>MkT>Qzw3tr;T&Z&Lt=)Z#J~0; z_IMK#*5%Ew(sr#x>jp+U<1of9wU5FZla*tQEl1eRaKi*R)~|A`-@=ZAqTLsBw#ciC zy>ItI59eZhB{{Hyuyw%|WZdD}=2$hv1dGv-?pTS(`=b0&dek>Qg)}e=@KnxZlh?@K z!UvxbKXZ-AX&3Ex7<>>Wi zNGJ1cafWgsZRR`&Q-`VDoWQA*&qqEPJzJoL78u_6ID)zz(ZlFAfWPfW_=QUo++FCc zPjD*NF<_&NkJvv-xp@oyzD_(R``Mg8pYvnSN?lf=;e51ml9#H$PVFCKGzkuB)HEL$ zu50QP?=qAuaFKPeRJ7sI#tzc?Eq~L!1&+E7u{YYN`6b1F)ol zY-!S4Y_4$Zz_!VVS4zmNc}$7l2G`(&!7n;4`HfOngUpU#*q@xfBe>^ePaJ9WLu5PQ zEJaDDFqNKfE{)iMrc^CV$&0yO?pn-1DHp&SdGna=nXdARz&-*!xsiy|-HpO+!slt| zevaE5K8#4nW5O!%-rg#N`*qMeL%}I(Pr(3_!QX4961sp-1jO{_1lv+?lF!4O-i^dC zt?Pl*6!KhT@Fkg<4-;1~x2fHtz`ZxnD}(k~D04Q=3ky+we(`4Q3f%s}z81~a$GwIEC&EeiG6d5ai zCW_*y7KQl3u5hVJ?J7l_QXIGhjNN15iZcR?LxtH3rywKkC#P|r zl=>z3|G?R_3mw+*y~{+5#M4(!a7$_l93ZXIuy&ZX7Puw#IlgCujVc^2V4!9&N}Ufj z6F8Q3rRQmp@1>q1KZqG&^gt~2a~h=`mNE!9oKI6-1{t2*)HoQiRM8dTh?f#rsw^#O zFzHe?4`9)r=6J7Yy%gsR*K7->r;Brk6z6QTKo%$OHb`-%ixSfo0&sFM39R`U+qPLg z!rg;#kKw)wB{(UvKU zH^|RDg0p=yHL&PXUwak7Y?LC&$h?y?*_+(;aJTJCaCnaeFQ@^IK~B_<$!8u~UjwVaw567t}zPXvZZ5F>I}Do16!VF$7LcnN~Z0xb=+N6!ikMTjAl`_Te)z- zC5JTZK3acf6-3Ye)@wMc>UsECoK90Wq+qhuEDIZkaZ|va;#BRl-uXuCp(G>@ubhTHA4cTTADYeXA#m9B z-9=Fp86poD7*@;X#5|VmZ@wM|TpO7EPZ-OX^>Sv7WG_Wp@j#m=y_$7yPJO52)Hm~; z+kU7!?2kjZX}8tnuSx-AGHBC!?sTlOh=Z+wyJVQ)zZG!gj zWfrDc9wJ-KaEP$EIJ6OV>h-@$!Ls#x1ff*kD_uU)M~HFyuJXrywm0#wA?Zx}3_lVVaf@tZbhHy>QGQQ-tY`HKzsWK~T3;B1jjs6{o zC%sT0k0J10h;S&VX~f?UVSdGB^Xrxu%}*1+M~^Nnj>U>&V<5%oMDmSdh37;+>%I2< znxUv<;>7pbn_esPI{pqhHE+iW3`T+4@Cx$#Z-JWk$!-Vo5nB$y9Oj#Wys|^&1u-Js zuL91*Al1O93L0j#%ZukQ1224tfKOLfl%iAVl!riD7D+0se2{YROU~?kAok8RPW%?Q zTj2(eV&i#%We>1mVGC_K$(`sLXw6Ngc55fpBI{qo_1{SP(g22IKep$uT!gHG8d+eL zlEE=p@dn$ivCv>_qug>?&IiGQ9K^1nvgDeOc@n{pq~++N(izk8US?`}=wi}pck=WR zY|>5f+~b&fgAJD>q)KNFZ>&|t0s|X)t#+Op%yrJTiz?u+WVz*c_oM51>%v;~)K8H2> zWoaiYHPcT1gg&B0MZ&Z1J~jvY6SUJ+a3fEHjLX?&x>w&sRx%%Svf6MZ?!>wj@|v7X zVN-^dZVzDdGqSh*&G!!Q)L45kEVttCd(5M;|2#Ma@~uw9eM5>6w=t+ppn|c!c4d6J9Xi_mAoieXCJa3am$iN$?t#?FllJo zotvn5CTqf!MApO-JYtc|Z+uxj7BLXysQCP;M!>%<4J>sWrv~m6Q$zI`lHv&AHPk|{`d4Y}11 z;l+|fjx&l;Y4SIfL!JCLH~90BIXR#yZKmGom%Sf}D3q4hwO^CQCDr8wT5Y-c=tv#L0=Lwi z?oP_?!Edoy>UST#xuw~$s_T!{zlLb*Ouh0-p>KbpPx4eZI%32pBZn0-Rb~lqSKoci zk<^$AtJ#l_952?U{-hX;panO0rm2__ADOJ68?kb8d^b`%x=Fn6HAl>pPn8{V_2jITQzXL9wXA*f%@m&5^^fXWvu|mpEk| zVWbVzKu3yH_3C{TXJ~E`UxFdHIxUzUu~$0vq0FU0<5`r+Tkd z%Aq{=mhF4fu71Hko&Q_Bs8t*^(s3NPm8L%X?C*U7ZSpOT^#$0&{LE3@_xk zfrDs-cy%a*z}(1D2r` z!+R)o3$$JL>P%0c!;_6#jQyiZ;YaS|*O(G?BR4tMa`396EEse77kZLKB0KF-0XoNm zZmU_@Gz`F{UIsC-M4E<~_WW&Up>I3GSkLbAm z9A>6wVeoJlXSclG)d?D-&VUdcA*eNgcB_^1fg_FB``nJXgeDTfjiN1>YPz@j&spujFgQM`09Ga1zF~USFT)Xb1T)p>cx^aRxlvhkh2A{^P zJP~Wg!)7Kn(p;rsKTgpeEQlEp)rzj!Fw00E)mBat3QL?PZDgpFLTOHw z4H?JGdTwxwGq@a9BYAYnird7@+hXQMS33jI*%+D|=;s91p`v0U#>0No-~1wbu<0yw zyyRkgR_mBctnTw4TUacx0qjkavNPy4C!GH% zJYl~ZI5grY#-$ZW>*0TH_Df(##L~!^|B|Qt4`#qZ&VWXogW0u?#2U~{Y+~w8&30#H zm!J%A5^oy`8?wUO%z@B;!@qU~7v{rCp+kMJ#a>{V9$J7c#&+a~sFE#oU<9hf*EvPG z(7KUNW_b<7^hDjjvmvkwNrX62Pb4Wpw$NSjn=tVPQ}=@ol+)iNAB?7K(P0GB)t)g) z`5I^H1XYCz%Hm5nE6fCyw4Rpv$ZU08YurT4MpzH|bSfGgLRgJ^_0>*kMqEXtI%Upd zBhsZI)(5EvWxiq=rRHN^no|Q6$L1a4EP`J*a&(s5KA(>6uoDI|YiNuDVNuOM5o`m_ zt_ji5JJ~QL3<`Pn2h*{sVe_AZ0gXOblYAJ|hvrU=}@19dshH%`-J6@VipRBB*G5j(GObOFG%cR*% zWt_LzDsUi>{r2=6??}eWr8(o}kxfRLi$d_gG{1*5_E`88DPw1em6SE83-|Ad9>rvMs=PQ>s&D{)>(JbCN4_x+8iseetYV7jH&`-a9QV3 zr>gT9)GKW31H0-23!-Xdt*4YD{vV-t*@R+nqGjUoU*;OA| zFu-`@=&D`MVpu@9|9Nhh zJ%7s4UYZ2E!(ee+WYLE<40JF^|FP?aTdA*uEJO$Y;Hz3vhv#^{iPtL@ExvMjXvr14 z03TYgaOuLu3l=V(zi6R(-sha!1t$vNUwJ++GJ?;>qv$tZXV;S+Faz%D z=|Dfv9TAJ8^!EhLv`b;&g9(oOvslhdFN(e!Js=PD!P5@!^TPA=9%h>VGxPw~H$RpU z@2vY(&2&-E_k5UEPtPD4E++Q%QN&>L(Mq6_^ySz zGD8n#`ui;Ol(b_gPIL#pSsi$H;MZk%V7Uvgk(yEelOFbW_R!zmL!Tz5%+FeWW?@#{ zf<>2Ii7W8SaW@^(n3u{`^|J-X;2QiQ+=2fZF2H{s7vO7g0e%VZzw`S0H+cJf$r9dt z|0eFXpPjX60q?!T|B?j@dG%c`!k?3M*>c>69}8H_i|>~$$6fiD+-N6FXUVcFgdkM& zb?8ob1AaczwLq@GFI#-&{F<-ht~K(LjmlW8_)Q@1Xxpm)k>U=;dle5T{z>r*=r{~# ztfKd3(6?0IrucJ3K08kLWFjFxr}&EEF-7iYX@9C>k>U)+xr)man-p!u^@=+b?^E2P z_?Y4|ib=&c6hDW7n(^l=p00SV;$+2HidQIJrMO)2dd0Ph-&MR>ag*W!#U~Xz6<<;O zSkaF(Fs}(8PlkR?^_&XwKj}NK-dDZ_-^Ukw<+GC z=*c|Tse142qz_d;2$Ley^CiWz6wgy!q-we z@l?gI;u(sCiZR6riZc{1QJkl^RPk!XX2tc2H!J>J@h-)?75ifXm2@eFh?ql9Bc6h{ z!GOI&82gD|z|Mr`$j4U{TNHn!=*d+0h3fYxKBf4)Vqegy8O{L3QxwN2PEfp1ah~E* z#b!lM_QH2m|6|3UDgH+BF~ye^Ur~Hl(R&LjjESA;8Uf^;_%W*Q_7)WEJ(&%^qCNWA zz3Oha;_nroQcNhmtoWv4FDw!m-zkcPiWe)|imi&@12SDdRQ;`r+Z7*Bd`huH@z08{ zDS9#_!C7E;%L8HF{#)K zI~tmMG9LIw6!YiFc=)2)7b>2kI9>5lMGEd^I7=0;R$Qfcz2Z+4?^3*5@kvF#CB<+C zVnIg?CySf={x6#3pJa zghdU*$yXc(WI3L$`iSBL#R|n4ik^&#<*N5&Ol(m7ZHhlryj$@;#YYsMQG8kPh~fu| z1F->MI?I8*zLb@9k?I#JHY(bRH!0q#_zT6oipPKqhwo7^+@Xpi6pIxvRIE{~Q~a*t zEsCDZiF;N5qT(xxuPgQk?+xP{t{71~PjRy1R~45iHY?t!C_FlgFF)I3()sUrbjJP< z-kvB$+u+A_K6eKvdV8YjwSdr6KsRc~)QF=3JXA1;haEgvubYX}>Dn1|K~hE)Evjfy zNfDnF6!BRBMx1hb#Fr*!fI8+Z6{=Mj##rKIfoer1ycRowCP2B<@U-Rlo^~s<86G$j zeEaN%eUNcUci=dvLKw?@qG4Nc}baOEk2@WC9 z@{$!ka4Oj1t#KO;PpV;lQp;0a@%USR%z%X)>iVeWVNrzaHw|-93?ajM6DI3TIcy5a zdIR1L?w3ktg7xMJ45~1XI?;71Z8B{Gq z$nH4Tw6S*Udt%^u385a#OD+v1105^B=xWTE#Nvm!flZ)htsM}jNOB1dOhsj7C=%Y+i zY^Cgb(d?2rd4>VN-^!;-VLI0d_QePy3_Iq@isUFCjp6*f8pTIucsEuE~Uzo`P)^dzN95(SDdK*PrnGALs zj=15b-r!4aJ8MwO?)rJceOJ;ugv509la=G(J1UPq${2v_Ka{{QKzai@u^nwQ zBa<^&JIGuLCdJ%vom;p!H{~U&zf0Nh;T)Ee|ky6AyUTHy1lb?vtPih(ry25o#&qOp4Rq6usB};{$>?D0D`1Yw zz>iFcmGJAhz4i{*Ail>&Mv#a%W0%6u@0x|9>5aUo@?R`+5TJWi_AT=N$o&;bK zV|H+Zk8yn$b>eH>x{txd!eyR`%qwC9UYA;r?wjnGQ-iR`xv+{bo^8X8el%NhP?JkD zLzS+qk!CAP%Wk>A9M9-#ND@6-nZrzJ4)B(dc>~B9&-^k6$Atu1p(Iclg|*X5Mfn(? zG)oNeNHjMDKReLMA=`2%XY&^k@9+mHOGE;eKe-H$1BKc>(FhD+9_#7eMx;0MbgmVas| zuYa=R_&UI>gh3Vs7fM{RLS8ni@85a&(A&wOsqI4RHuatQDKx@3*^{FVwVwH4&n4K> zL}qCY^P~j7(S2`nrZXyxL@<7o7*@`AIf27Y#bIkQjLKtww*wt^MTcdJtH!6A9`wlz zKW4p}nuR;6@P;{g2m}R~0jv2C4aY|jsz;GV0|%=w>blAvP)zgaNkWSbnwVu>4O;a1 zphXXM2Ga#@m`P>T|0ZQKIB?QBRY_8!(H=cYw5%d0n5fWqv6ki7XUAKQ+)G0Aqww-5 z3DNLkNYL!p!z9wc27MlkLpxr)lBC0FjU9LNfhCFG4m@z=2Q+WDupvNY@%kjL%Too80fipvnKuV;-i^g13ytF~8#;%T(^QY8g?v1t%KYe#-$?w?eWts4 z(0d>4__4wn{upZTF+8?s?+Zae`%*>E-R*FPpZ8{Bzu(SU0HaZO0~ z-nX+yK0LcxIPlbTOLtz_)O&U~%1P&y=8wQ#Jr(+S?ueMe(;v^0=D~o23P@T~&a4w0 zHFpbd3(j1ggPHev;dy!wGtK`Q+A!0>k7Yz!FrrPD8TB|;7h14qPug%k{#fs{9|2?s z_4K2m4rSLt`K2 z-MpWqLpSxZwTJ#UJ@mVK=nwSJKiNZXXvaL{o1X=`@l~K713(W3DH*imWedM4)L%nB z9(|^egCX&}2xR1QKt>)5GICE6vJi&H7&7tMSzl)uq$8824Dsogi}ZA*DUUTYWk_Kc zaq1vMQ=Iyk!VGe91~r+I)q4_;J+n`fnjwf2dF46i3}CNN7oB;DnzO8FzeSN{NqxIw zhhj?c6U97qLb?kn@+vp=S15j4ah0O2c)KF6gU~%MlM(-@=+T`&R{bE18?+yyc&1{{ zH;SjL`PURzC^jlOir-bdS@GwJ_bdKh@j1m06#HY4XF3Kco}%~##eY{Er+A*CN0+Wp z{Y=FbimMdYDBh&_3&r0l{z36&#lI=$B27%!V8yA5vlK5?T%=g9c!S~(6@RXHzv5Gh zd7|E%JRik^)9 z_f+5CqaQ1V6i-)-C`J`M`t~KNzfy6DV!h(G6+QZPtLi=a_9oTuQ#`2njNXg*HyLd9yuYZO;2-k^B1;(sdcP`p=>S9}@nqlyW|R}_ybexf)6 zlc1zSagyRR#VW=5ieFQ_R?$}cuHsJ>pI3ZQ@h?EquisJq;Ln+Ozo0l$v0PE!5Wpn- zb=5CdT&dWq_+!O874KL43y}1;BdX`UZ02*C;%voB6&EOeL$OKmKY8qHpI85iWe!)Q@l#?8pZD@-ln)k@jk^z6#t<3zG7c2hL|27 zkaW5)sD7m4MT+wj>lMAX3RbKB2E}_7A5?sdhy~TtL@dDn1nd>g%6fx%8YUB^Gy4?B zC{9$It$4YjN58&a^&1s$SA1CUQN?E!KT;%zF7rD`@l?gI;uV+UiIl~~9=R_qlYUI> z#CP&X$HuBq`g#3UPOg}eEo{`t7rtz)ZZVCezfvv~@o{a(6``-&ZUj8tcx#>~JRa=` z`{Dv@8RO=0M26&VeGI={cO=kRuzz*&%gu4bfq-%xV%y`ny2ep9&$}GH7u~XnE^t?o zVk@zOPWYbH+bK9|#Sz(m=sx}{@Se+4eUcF3xb}cr%E|#zsib)21bbhPJBN-QzkDC( z6rUj2XwrIiA|H+5*#Uhf3QA7G_0ea&ClbGv&E0*;w{X3lDfhRIerf4@MKp9wD-OZ!6VJbodSE* z21W(RLbQkIxe*QOErxFN4qU1zaF_HV zjcf&-nP5+~pKt?rxJz=>^{@s;HpUHXfta5L1nMrqaR*ai7pzMFgA;vW_L-SwEJ2*$bv-;6r0z=7u>l^`octH zewh@n7md?v^Ew7=#4MuNBv?sxH6xglYY&!kYc|qLi|z628DPY;Vcb|?WY!r-5Lb#2 zn>d%=;(K90D+F9=%tiE&bu&2U#o<;XZz$3Zu}bA|;XooXgzV9C11L*dr95!YO9OTz zd*QH*4mD0AjE64NTbX!co)KxO1liqpyqoWN>Y~dxycN^1S@PgO5~<0QYrVSXr5xB& zmeS@rWFJm;K%KNGDDO6?c)z=!c_x&128@jK#OJa*aCs(=mZu~Khm1#NHYwx;5KM9* zPZ}apv97z5&gx{19I&bxcfqt|?RWP^goLwk}!IZa%QC(!91DPw^rF2vKPhxT?0 zt(bXPFBR7<(DU;dXs9cwJSrJ?;zERqEJ(#{l%|;&*m=O*uwVfk+UxrAO(cj|3zexb z@~h!6Ik*%7!Ig;;m0-#v#Nf{lA?EUeu9zvDjLA=K)6?;ys#?{$*AP+{Cp&bd84JoQ7+MyrlVVL8kdol+VpT9nv}>7-wQEQ zkOmilUyK4F07PZ8KkeRZd!&A!}CI5+R_%481(?fV5BII6N z(6qO(X%Nly7fQ_XujJ6u1DuP7=cH$97 zn-2GB*`1W9I4N9f^X&+)z4sRU!Wz@V2mr3pK^l)y|L%En0n%Z;m zHfQU2%qw=0RMIG^o$)MdCmO~qXkjgoYY*dKVGpR`Z_zydj+ZJJH5cmiROFa>;pq`a znm+2|Z@U^46>oOB;Tmj{j)z;|oOh14u|Njg1`P(oTxgp1^mT)Gb(^A)C$ZVxi!+rs zO>N!)Pi~aAuxaa@+VoJ4{bA;0<;HK2Im~l0w&|hnGuAlFPHNfoP;azVi$!PBKE9a= zG)A1$)-Z|dX* zdHGbz%Q=@^fVl*gEC|iO1svm9^~{olU!I4eV(2ts5=|zJv{3Z#w_wCt#g%T>p-eSy z1Va?WykIoJ*#00~*zL(#Y!_ac^6d;AfZ1{#TpeiIn>TW;G~lLGZ=DOw^UV+mGq{GX zHkyWOnnzPR=YpnvoC`ohlYvP`pkdXFQV6C=k==n|B5V)19j2K>IUnK1P@c!z!S=@( z$pgs6enw;xjriDR&8P_xD+S1ajN!g@rWIh|4nS05?+{&8h4T{qv@N;5{U})oy3k@p ztMrx#UF9glcqzOl24bA1i*joCf=-@^bK;>rxMQEl)`7WQ#%63ma&bF3jM>ST9BM{y zf9o6>sA~~`J)UJ{k6M6V?9_Z1sq-*W2kc?&ZJ!>aS3lT{axlcn!MDN5M7JKIvo_GN z=ygy=vI-#M!XCT=Hg5F$_+^bq*LgW7X`O^Blj>fo3W2PxB< zBa$26kH;&72A%Y7rh@ITXAR9`u0C=`ZDCwwr-PhX@qMNfy+`W+_mp9j=o3!|keK_~K^M1PC`12v6U|6}l5!s5dUKwgw$2};2?ZZkY(sb7=xs^~Vv z-SlvdEedoUK4B$gdBpYo(ksDiH~vfa>%BI!=yWFZyVvBH612y&T;1p|opaJVMVZ*h zS%fR)CNZcuq(O@bJ>opk^ zWHHzH({2NybhA`|>?^waAAcJH#0~nnO%U7Gwf`4mG~T&R|EAr&WIbh00C*WedF4s>7AatXO z0jT19mLTHce4Ok0PSG`m?1e(GGj)NA$7GEyC)$A<9D_2(HkCnOxnUT=WLK-RvNV)( zE+(pxFz`UJ_4JpmsSke9CKwCaY}_6;4{<=!*FFZ-)SlP0FJITm+M^3$k02;bUYb>8 z%t(|$)9bw;b-EUfXjIQeG#Q*Mc$EW3afrRNTT@~dF4SquYdwj9-6t?iPg+zm%|jqY zqQ4^p<^<%LgDBgT%sAaf)0^yJEa%h?tl+)YB!ene>&>ue+S5CuL5U4|ir75dZMAM@ z7%qX0M<<`lb+gpgHnrVbtkb)5!o@n4ysKzwMENxB?QP34T@Q4&8q3L9o7ccm_X8a? zriP3|omvR>#Q6)PfqR3ywnXqhIc0dMM4BJuOWv)@8V3@IjVVPjHgs>4Y>-vq|HIt3 z2S!<(>u<;cDJ*W#MWScHwOuvH5(8``OM(Un5G7)OaM7Zof(;rq!lLL20Zd}~{8+$B zz4V|$(H^U`-e^lLdH~U=)fR14(5#o{m2^|_zBWy?ta_x{p!PnQ(k@m3>Z5g?&B`o!KsTlpav3oi zP5Nl`+&NYxL!X?{P~c@-%&uv_dbXnq3ctei1(QDNDW z`ShSty5NAfQ*t*<*>c?IPtX;xXzaX%?l1>Y&HcixJHUl54#ug#vnm@_v{f!H{v@BsuVn=Tyk!DA%4w>SnLR($U za!s0Mmb(o;51HlCDQlLy6;``)yM-UtnaG=W_TqTNz;*$Zv)l*i)6Q2l*_E)=ZMwRd zfiRP#=fh1`S;bw`)eXkxO;^_&n>Sr$&M>*W%{XRFS4m;IX^qw@w&#Lp=fJ@}Y99x2 z22gNT3rRx(XV>Cf=h%T@@PnSp!NV|ijthez4j!hbLdJmS|7~ZrsvkL#eU_bei)pYB z%fhGG{*J600nw@rqJUUxCXQ^YslZ_5-;fR68V=n?1T3Gj=XUS4R_&dcH)pL5V(HNw zB+L$v4og~MDV5PgKsa%fR5>~Z%&Zb`2APj+vNo6)bH)W+PPf<54EANx>YX0gygk1g zol%La;APW1{P8%1p6)BpL5~}1l?^q2;76^IpIheYypFgxFwA;W{N|?$ns;(q2zkt| zM`bMurUz9p;9;e*KSOH}xJcOf7=5__9gDd^B`_((y%z9y*$OyY0hnbtn{ZtG&f+X~ zkL$gBJXbT~FWXe%AS zI{n3T7?B>doepoqp_C4z(eYTg^q{BVj?TzfjsH=`KRP61fU(n&^spk$n>3lt z0VWM`f1O!Q!`Om}q&t8)z-kls1|r-Wh<1~4uqA*pVY7hVz=kS71hSq%Br8tn^Y0i# zk2zpKjmR`bwPB=}(~qsy8AM_@V@&fbF{IdRw~J=@oEKcvZ!M!)a~l-rb?y%QB-iW? zgb^4Su4a6j&5C6=-qX&{U&ed*@vywdg!((Y#{~Q`-b2D#7G=GCf%p7c9_&hUGnV)} zS&QX5Ut}$;H+13W09_mg#ja$rTg=+z-(xMi5bp1>mhJq`YT#AO&Mu6Ix6!RTYhm#Y zWd&Q|*2!8}JcT*b-xlM~v<8p&WU&mS$F_{#xyf)9yM6v|U>SDdT`XgZWf|lsr?F%6 z6B#_&t0ir(qp{_~a95|6n&>I&_PvkcsqtZ0iBbHZT*Za7qs4 z3w;pCle|~irQ{a7{#}pNlj>+O`cMoW488G67L$UQN3d@5Y~N=QZQp;BroI(ep4j=tmE{;aesLbuepWyT zDoh`R_~MlOnSTfD$KMsZA_!qtma$Hy z)^B%oUH|=?^6@bhw)=itOcUp7-YQdKH#Ru!&p~Ze&{O;aETC?)@3O8kHN!33@?(a4 zFo{wg)3QShB)bY{%%QcCWbXgujxjve9?Ed%JO*ZJNNSs3`&XckoC~16!0GTPSVelU zGmHV6@SXt^$P^(KR2DfMeuGrmn)dB$mgDKHQNsl1KP4gk)=C2X^C~ zkBRwLLZfC@55&Tj>9;BWUrhiz-lhF`yj$f)f!SuwK&n=Oi3&d3mf9W&y5$8!J|R7Z zS$eRI9G)KYxJbMYv;IoaWQ!StvWFNfM#dgDE5u(x3Z@Ol-?1yiBoJo5-DreM$fnu{ z8A|!NPHZXV>;tVZr8Si5lbYVcwgOK!{2}^84H6(x-C$}F7KlkVOT`rQ#U6*2R^tq! zD8O}h5fX1vTkhqOke_uC5+=hcp=UyTFiQkO->b6RuQFO=7mislZ+V`Tjpg|+DtGdw zy>CL!fDn;QSx=Hdza^(|10#ogIu=hH8aW1~s=$RUxMvFu?{V4peJoE@gY;F|)Yejb zb_4Ak*}uYdCe=7rs4!Za2jL=REOyqnZ;cAwKR4#;GwY+#c;(+vJxC=5% z@z0aqu$|ui6}Yh|m^7fn&ES@d>2RoMyU1U`GaH6A-PKLBvYdB}>4Gb;I*fQEF0~-V zZsHOhzEoV|$HR(CCX^AEY#T7WIt5X}Ox3cMVA&?RS_lUL?*xNdh?z$%XC}JlQFxyT zIac>w^5tR<7G%HJPSCd-6#9z-PFJ+`wyl_R7iMJf??eMa;JQsdHg?GsyFrk{%M}mvrYn}HF}0vViw2mJXlV6dCUyT< zWGL6Pp=+IUJ5sWZ(MStsQoz&?FBnK1D3>_UlyU}@W&X2GmH!;AehWTNBAN`Vcc{g*} z)h@NVq^4>0R)4W|La4os;jFhWHc+n(S{?OYY@-OjHY+?Si##y*hYHuL;3gqlz3I^A zY_HC5^8X7hnlo`TlzH=UN!6=Nme6M)me{Uh=htGJR=9?MYiOwBh5k`)`Ou*_gNKYy zvYfQT3f+enPoCtxWj%vqsfuP_icT7b>pD_oo28Y#kB$*|B^>{8Hz>`Loa1&?ZaV^M zo@_dTS(P&#!E}i|{QPCIa;YaK$2-O3B@_{%M#&jO+C%jV|Bf-eWSHqC157Wup9M6` zGcy2B2-}4?yws&@e+T?>(ttP7UWX=_3OJf0^z5LyI37?|3gs#=FI(X3u-R}2@SB;y z`)|eT1blW0x(DdkK8)eZ`eP9l*z{5=kT%hmBUS8&V|5_y?>ot@iM02lhr}!C@DX^V z0LI|z8KBHL_Kbu_?2kLFA?TAI2%WQeXe?3a)Wdy@(i0&_ zo#gZVYzXcv$9%q35d@qxe*EZ2;iM@uhD1gdjl=~=U(up#FHc^05iq&XVx4DNIKRFq zIe$sgS2XX!dE z#|KK8`>QDW7w&tn&x#A5jX&a0{G)%Yl9=BH_@hMO{rHVP(8t8z!`SflCj6DkOz_Lh zWN`hc^S8Si`VnDc{%}sSGk@hUXC>p?!+=>o?;C=D!QVe~kNaK3H{&qzF{2UqS z^X*3FadpVtD`h$I@sDNjXab{e|0tjDZ(gQg&oc6J=P%p+|8kF;`QVRq=e=w+X=7%- zXdeI!;GbuQ+EkNY&(6E(1^DNMkHQ?uvZD*&mQL6ABA7{f&p*gv>eaKejw`ahkAb-= z%RV0Fnk@SnFwe$6FF(AaJ15Kjb(rU7+2_H`f1dx#VXn)vUk!78mVFt_4O#Y;FekI@ zH^ICl%YHk|jal}MFfY%te;?+SEc-(+Gfpo*KZSW!mVF1zYqRXnz`QQY{sPRmW!d+@ zygtiLmbW3x{u`L@&a%G?^SxPi7(0KwhyDR<58_`Q{;@rL4BVP!{|n69v+TUO^>mh< z+K_f<+55rHJbLjR1^b&>_G4gwC(C{u?E7K&=u-&$pR?>#M|LpFJ{tDVv+UzxN5(tD zb70_L=fyVz=DaNX`7j5v?B9SnKg)h4%$)Lj;je+26HL#(3}#LzJo`6cj%3-XJ3N|Y zzZGVd$@6~~%&{!{f5S`x(ECnhhVd->BQSH~?tT9m%$#d^_U$lN;GakDHkdiYdEcLd z+0ew0$?tmsc8{T(s|l`ArNW&De~i z{m-yBoC47sVQBYVqRWC8`>wvQ9$EtyKxM$CP#Hia@gseUs48F)^#m*$2}J>m;?NYZ zs06A47M%)p^NU7N-~6IdDxBxde`p4Pt^pWEQ0+VoBaP;H7~)hKK$jAuHvooHseGO; zh{P%mKs*ViJDi#WfY2Z?oH(**gvn35Xv9d`ONvIsiKiBgFv{#l6^%HR_R^veqkNYv zgu;VTs52Nrb@(HTnZ$^qkt`G*_&|9^qEv7|u^wTv-l;|LQ&pxRANe3QdD9}cWM#zIKls@q7qZO(xQ@6O{q$#q@l!+3UMT;{2#YMj~@E?oSLOOgwX-UVn|uZP2)7EK622`wAp97@0MqS{f5akTnebBKHNvIB&BBL;TZNu3g3n~{4dICK z_7i$K2nuDtN_eQQfm`MNec=}29^vnW`-FcH_R?Mb0^!$$bA^`+?-Jf4ykGc`@F&89 z!kpf=9KD5Og;xlZ!dBrL;qAgr!XFB^3V$j5ov5Q{}7H4o-UjqtP#!>UMPH2_=fQJLQm&<5hg68 zS6nz+SSdVHc)oC+@CxA#!iR)E75hj*I97PS z@M+=igzpMH-Ru1!H!=Q!!Ybh$;YGqap(9)){J!u3;Wpte;ctcS3;Tv_dPfOQ5GI7D z3ug$wE^H89EnF+SMfk9AtFTR2fe9wdcb>3O*ebkRc%Se=;eO$#!rn*Qc>Y5;Mz}=S zBy17hC|oD}j_@bKmxON!-xnSf_Q0AC^PMj&5}qn77mgEF38x6>3X{U?glmPj2=5m@ zBz#KvoN%A;PeM+{nXf|OX~MUKeoWx`{Y2p@!l}Yp!t;c83x6iuA$&pjvG6ZK>M3FT zG2v;#g~B_8j|+DRpB3&FzAAiEcm(DUj5jVEEvynw7oI1)RCu-UJHqb?HwzyXZWlf! zd_nlRFdDY$pDHXDP8H4))(aO3ZxpT--YR@ZxK;R~@J-=I!oLVd4YKLa5?&*`Rk&67 zrZ8`?^*>ZNNjO`$K)6DA3kyA@e?V9#yivGT_+8;<;g5wogg+O)Bz#xc zKVsuQUU-slnDBJr1mR@iRN*Y)0^v#`ZE@`-EGBj|!g?riFhM_B_GnV~}vDaJVob zyi~YWxJCG=aF_5|;hVzugdYiyM_Xb09wIzNI7v87I9qs?@EYL_!bgR>g$IO3oMht< z35N^IgkyzY7hWj5T-YeQPx!EKtMGB*%ffer?+ZT{_9(RZI7)bo@Oa@w;T1wxc(-u7 z@CD%?g~1^<-eZKv2~QVJ5Kb30_k^2;4-0=Od`tMY@N;30lWjf*3I_>G zgk{3)WD6AJ=Eo>BS568mL(>RJB0FQkcQ9!s$XEemOm~o(jy9Js`{%LL4^!Af_3_ux~ITj0(}+ zj615yAd)c{7hba9ig^tSu3qFRU+a8pY1H9$uZZ9oxY|t z#$x_h-D}(cu1Mc-Fvo1m*0=R6#Yb$XcBBW)g~=V*zB&(tX#X*n*05#F=b~{uWbZqC zqGC3D;3WhQw5?|?%!mXhFowVA^h?4te0y6i09W>*zk5IkrcI=uGu7`7JQJG4ab~jt z_O_ljhm5KRqQXaK;F-bI`w(~|<7ve^CVZTdx3-}|-VGsOIoz?uT$7uBrZb=d7Tlok zR|7O};FR^GQ*e!gP}rY_9`x(&YwK;5DSUuqKh_XF)w=#00X4b)8_SGVo5sA3o{W6o zkFn)EH|>AgUhaj)ICH&@%HMO+<_2D{bp!nEc&i6IB2&29!Pf@P%xbfD5Q6Q1-SqG0+L&M%@_PoGUdhSKBsUtSMXYbC}KYaa} zc2glX1Ll!|#m8@CWq~{^|BKa!xfS-scLrBc^K7tXmUB&ViLgH89Gi;sJr zX}^Un?u|EbuFYI|$C=TAhW7kyo1Seyi}RT87x7{Rp7`mFLgP_}m^loP-m~w|8<`X` z0X2KqQx`sq7F7O0 zz)Lsworiwp432rG#?l{0OpOa`CbJBYAQL~apHky;HW}yHbbd8+0+XO}CTIvuJlpkV zSzFI)1m>@;XQegpycW& zKRx~5ac1O79v~^Ycu}(SUq3X0shXi-FCc#v_%}gg0_|+<{9(%6?My~ZAM7!s>wN|8 ztOGy(<>4PhZ(}z+9p;r;alvZ*5g{5G|JnYQ@PmGgi$6AK#*Za5^J9G8H#*SFe`D~E z{=DDXL(=uWodpk`nSSZdi<@@u8&VrEh@W=Y$UO$!uJ84EcmSRjDlZLc^6-YMb*)i4eMexrH z57F5d&9XyeGiO1(?;~K3Wqm&tX4awieKgD*$vyixn91%u`(&6ovU>KZFjr*RXTe;V zWj_z*D*W^Edoj#4S>G>*xi-sw4a~Fg&-1?m=DAsRvc$S9`?p|jz&|fPx5J#wvcuT< z`)73g-!0$lV|K6H6YehdU9zB_yXA{;aEvPyiVgG2uwPz}?eZ(J zTYd?}LTs2{Zh~RYya8L~*i^T)0?xlkmTU_Xr;l@=7Gr-z9uk z_<_*d>!z$ue_s&}6efh@g_DJ~!i$8B!u7(x2#-YnVZ0IH$-+|Mg5<*am#{@&d5W0{ zbD=l&eB*hl87~Gp*2RB>TYH4R?1ECbRXhG89N6%}EYys+?pj0&QM*4*XfJ2{ z#jOW|t#`r1$F*vsOQs=(B{PuhY`(Ns%10CNt`;ta@O`yvzK@HC=jx;L=%spAr=n=w z3Zkz<`YNX{JfMaH|9pe1l8;Q8r*zBh<7UHO!wsw3n7BPDJ^V$Sir&C1?20%?JLmh` zdZUJX4ldW8=l9fEyBGLv>4rZu{6N_SG5e^LQ$nWi^sC@s^Qt4B7qdi2-a#3)D((Mp z{GO+6&~`I(Ltv{*q3I>}?0lym*?igAr3h#q#B}HUNC97+h=9he-Ar7|uE9kc4mt=3 zsXA>O(oZH$t*n~Yl54M~Q zXS~T>4beby$#X>dNG1!W`Y8&<;9KGUie54QRlA=1c>@Y!I?AJCBP zBfsfp2H498pJ7B5uvvw5pbK8p4e%{i79On1*K`u{Q2Qv2yhz;!gt%J4dZ0t%*`|HA z4dRkx3qR#xPGg_ty}lSN6>pN|-Rlpw_CoS_9uf((FI*x8h6i*$98Hcv)zCV8d}nzH z8_aB;8ZV_TaIuJYPxM|wb63D`(_$lGFqvJ5%EZz_3vJT zOJ6J_TFq-{UZ_H+AFQ}##-dr3=Jr+7WoPSo$2lo{t-)6$OPyP(P(ixKo~PSUG7^w~ zk$f#K*tYi=n?BMuAbzK8fQDor*KB&o&N%merXZ%p&i0b27^q`QPq zO&3p_LCx&*_yF}>7TJ6E5p%{YH~XM2v(?sjHj5+ZG-e)a8)8p1%Jd%d zUr+jKH)|ngfg{+$(OYkenx~LK+a=CmXNuo7G3ZTMTyQe%$m{6L+#WLro{$_U1u>>q zX;$Bi?_><_Lu+ZWtvyk^^a}JxkA>Se^z4g%VCPOr6}&ows_{3t<~2-Dv+JXizmvU# zm!;x;(!Iu`W@^)Tfg1};maXA3EqHx;aMLd`xAVT_y6AF5*E~8m*{h9m2VY)XlFn^6 z3khZlpNt@%jp>|rqrcKR^#fC8IQv$n=KAmm{a|TOuL7SukL#n$Vbl8CtbjK-6$jT$ z;oUu3?U?HFqUszjCU9_?J+3|03(3y4-rJ)&>_ug>iqqjD6{Mo@$s(V zt@bd(8=m>|hPPEFSGKa+a?qW8nLlCbzxNq1oOC!^2M6*V8o@d};}J00o{DenC3&>M z$I(C#WD8;N^g8T(LeqnZV#SV9(A17(&AZ~LhS)Umru@uWvmB90up0WYQfsEVrr}Mm z`x>J%L)6TT75q|%Z3?UeZ~%iRjw{paD)85Nxo$XM#ZydYrlO9b9%3F3%+K5oYGILQ z0AVi{`UWuI-p?{&I=q(I%vV2O<*JQUh=ebXzzKf%i$tnNjK<$-6Q*A)Ttb|loZm3U zcgD1dv{a86} z^LKYvT(r|4e}}G%+zWr4uX;Z(7#TL>=X{$#`kQ2p<}bhT-|0fn9~W#cFh1;`h`yWo zTbBC;l5ssJ#>F4QdS+vXzaweT&--@h`pH%BSLb;Gdj5!HZQgHNU))WABf#8KAzeso zX2+u)jJ|r%c@+)%dGUF653}9>mGu+S{hwJsVY?~7KhJ*@=17)(2+W09c5(>TrRP5Z zGg*jdKMm%JEc$j89>yGWY`SlBApD#=bHwu3xJPsX+*fAk;eEnK zgpUiobMha`?wyzS-t6m(83EJpFB~Z>6OI?2BfLP^AiP@GDs+Y45pEDZApDW=O(Cax zO#hFbj`y(+3@w@jn--WU#g?9)a6+R=(2z&Kb`Gj8+P7+=~1jD{mxLD}DrPm^V ztK|M)!tWBn{CUp42hIxqjEDv0-E>EO_XuAnB7X1O{kwACFZTno|5ca^Uc-3%5E1TZ zAmjfU5%HJP9r4c;)?*=beuKBtgY})^#ifZvX=22P!>{!WkH@vx^N;t(pZ*#;J$`ZX z_wZ{yEB?3{U$F?Xovj-PJn6K7j$4c( zOT_XHzgbOfczNbFezO<%5$Aq>(_}v=m%-r99>B-_Gu8L@Hri~MOz4V zdH@X~jo8gw0_Ac^2P%iL0bP$&{opM~HJ@Ph+u?$I9W+AB#mA`q$h&Pwy#RpFbKs#G zeq*#^?F#<5_=-rLV-~DhMC2sG@6e%wAe9JROh1DWHjeV-@moD!80TCFil5-Ul;1ZS zb&#AX#gX56_*@F#0qYwYttpwe;U6c;0fRJ!I!$4i;F*NjK)@Dr(|_)LAF_U(B?D3 zDM1+A&;Jqra(QyD8|clw?s*VlFxzYFz--S%H>ty8@R1OMuKIRHY41*W9U8!+A-*Rm1*H+iQwuyEIqaLjKYz>!xE=yl2Wp1G?(9( z6Kwewrg5pTC4qH!W5=S3s-4*2!>85sQ@4cav>xb6rRh}UaE_u6-|Lw9omc1EqRZjE zxx6=$_v4dVFvTT3-vUzLh59KNYh1MD9|7qum6m zcR4;L%8yE305Vs(ay+=jnRUoFWID_^U4r>ohA6m!PV5%nw8^iHpe*PfFm2Wwbn=H zbZ%~&PBGpwfbPuFl?`rsIV*xywp-<(Ta9-6nZ&TJ+~&U#UR8eNx~9#4zi}v`kBN=} zH0}+sm5pk83f-J>yNmga4Js=I>&xv8dau5lo-9!VmZ(@yb3=VwUtD}Os zM(`(LxI5+qsGyxYN^!M6Mm`1u_mtH7`fFRH&CbB4K(=(;%lGlXUyoV=;%k zbvZtn6M;k7=*A(gp$RnY zUky%7M=-V}iTLfomiG#LzR5O$vVx_*v7H!I+mQBuviB`89=3`0?>wF3Eo$YX!mHZ+ zKSVWjWPZuBGnR>_LJzoo5O4_^3Iadv#@5(XPjx0L-9Of?{@Cxl!;vP+C(1ul*LEID%^=ShS4a1zvJ9t#vQvr_6<@ec9V^zYXqoqL%nfIs^u30Os;F)SPpz` zWFdH}4&yW5`$7-uV|q|L*NNY3+IofU65=yGf~$|j>WtDgc$ISzqTX_QV<&AueSVax=Zcg+Fw&XIq)~g%Kb%xlk zJ=U@O$a3Yfyrw%zSUzw%cPf0d-AqT@xEE-5ztEUA!_o%fTS5aEtsiFSuius5dH@`b z!$qARtq9%a0d$wbjr3cwiGLC2dO%t3vLg-a34N34xq(|+pGjtq`&Jxq3tQi7!bU}y zAq|IgO(cd5SuKMr`6*Nk=C}%`p|vHb!$!z#p;6rnDBjbz=^@t~pL9!1O!my#Zg&ie zFy!gP-z?kh+GK!06*4&wu4zP>$zYSf#IwQG^*}2UnWDt*a!ljVP}XLSK$=ACpau2k zcvIIda<7Um#}~J}e=2s|S>O%SLu@*SZMw@!IvYEBA{u)w2Qi$vTO0%#3O2E=S)bYM z{pao&eqdMl4D$lJzsK8^pmzy-o|R>SYp#dc9TVYSzVQ&-iufB~1RuZGbdJDhNM^R1 z{LJqJ_Sw^0uIWWia-Sb9poNh=KQ#6z3ckb*uR$HwI&*%A{R9(f;8p~0>f9Rlu+{PVZXsv`3BCT=#F6-OqUhqcuK#wFwk8$2p?Nffo<*2=rF&MuTU!ri7ivC{Mte2* zpv>P-WW9G7ZGO9MQgVJKQD8 zrI&Nm#DUo&#ykOMiJ^{;SutA}!IoFCqhif&KV~-ZtYix8j0M-Mpii@Lu59AS0p6BI z3usJ*&=(j};$+lgaWIuYOrT-|l!CeS&;eGDr|uf@)M#Zi55=+@af>5PzXF7D>^}Li zP!vYnuu9{`*wEgJ$Ko9zc#Oc>^i8yfF$}^A`#zX~TN0o*^Q`PdkgeJ=4o>JNu8A5I zI@ddPsy!)oDkJZ)Q#r}U#9BymH}r{H{fXZ-`Ef#TIMr{!VzS7C1;f~u+yNE*Yc_+N zBp!tbePCul6_)EJ4sIfUUly?}8AHg?u3^gwd;Av+IJjmVc6v;p#KC35>|W;hR1FTV zGpJ)WQjr~qvfp%KcNvdmJ^lF9^eeZd5NHS3{Z0uTgDp3K23+FFzoJ+>M|4os>mz6uefU5Zc5vI-NhwW8h1Jf}j z^FIOAb@mgH)u`k;6`>H9&Y8D+%0C6%`LLR zOa~^E$#E@i(@mzsy79{qVp{Nn_nFs=5 z)=NOLD*zMr_sI}FPIz5 zSo}_9+J_gf$dXNdoY=#bhePJ$%Pg3mn3$jx2m#2r!XG%6qZ$91sjNzCJO{?~p3L=> z=)thii|V75P(#d_Pd`@L-uHv6e+k45l=mex@~TVVHg9&RRjhudhlP5BSTXn5@o0q0 z5y}pDDM+C1DY++8Krw|3uHmAx^U_-N6fAwX{+mI&%C!H9&TfHj*BK?@W7` zC9%8nEQ?JRGMvtz>@>1qH5Aszv7>$ldpTs9*ln*rgT~1cfd-~P!8IkO_{bfENj9j& zU+qdt*LWRVL*+Ce$Q(EH{gnUP#;@cKGXSMRxtLFGi7v+%l`+uE9iBU43OIo&;ZhSXL21#fuSt=UAY$y3w zw7>{$X3ptU|J4(rLD417$3tV^!7Lgqq1LJH6rsbnf@%<K*?Jk@~+7Y^|grtX~`=Pjgf1{~vk!RkD`9BTe&K-QlHa4y+NBl&zp?{Fh45XEK6+ zPJ%X-&l_?kKN^sS;x3$8ffEXL$=4X6?Lj>^JSr9HduHN=t|d~4#8!;%#|#G7`~+jx zMjF+%_P*up*z=;qVjjT8(V88$OQo*OG3zpBFlc%fQn7m0Em@NEYmCZn+O(&PB&}D+ zS|v&Mr6fI;lC-(wba0jeE4`wcwc+GkF&INj#whPH+!as)SUmpd#UP7b`;;f8`X#vdzXyP*%P zr0ygkYx5`{#O}ZkC99jMfR(uEUJoyZIpY-qt#g|JEAiLh>Urikm0kF<;w>6U$Xw4$ z>`(T^J;UBp>^dy6RhbTdk_k{9vYEs|UT9&i!w=f%?IzQ{?*?0c&OSq?SiZ-t-_vax zV>>p_Y1x1F)EzDe-ik2U6PxU6$Xthy7+T-P(As&{67~k3J=-f5|BSIx6iWMdLkzV7 zQ2ROF>EYXWLTyYna|~YXV0&Otgcj?>6&A{|)lXtw6G8+U4apVyn^XNazcY-%GBXha zk5{5S#M^oxOC6cFK@IOd9Trg1{#O}Gs_{vmWYbg9$7L4bV%vnw3YKASW&^-ABYdWr z`qvG!CPU6V_YtgiB8K^V<}q3=ySIapTfW-0r*ttrb4<3|kZok6Bl7@Wiwm~q^3Aya zCEb4soz`DU_lNNjbUp#F7Wn9XLjZFa)>yur+V6b8vi&R6{vKn1%-!ZQlwSJhLv(Lb zNI5*cA9)`khZUmAuxdBCKV`uYa{`M}6G)WfCJPQX7xoGOOZW!~X z-e?9`WW6)YKaH-dvDuI8@K?UsePwGVu5wtYOR)i|-6 z^~qjSMOdf$fzR!P8Z`hZ=V7D)=_bm*hBy$?jU`J+X^Ae!=iJcBGZQZdSAWPZU}goJ z4%lv(nfQ(&z9BqzfSmAsnWHGo*i}osleq6?bu`TvoIxfPt@LMnZ^JW|iwyh362Qq4 z`AsLs1_TJ&V7DDo;ZM`K`pPX1BjKk4``!NT0>5*a-#JQWqK8rFpMog_oRI;?WF@of zx6FM2pOE`d=4kYZtaV;>)fnCvtA!Wj26x$e<9+Zm63=r^;g}U7Ebf{;NKg>1;Zfub zOA0GmUt64S)^%A9Gw*TQCfUK3aW!Faw~BGrW8VhP%wVj909wPp2;b(v$+S@0t=KjH?uxaQdNz}>qO^`CWGd-|HGwui&(8ZYHE-DC z#F2$pUbBdYbR#%QGau(^a9s9;Q9K3gt68|<@(b%D3$D0i{)LMcT(qEmLGoJoO3uGH zIe#9`6thJ7?f*C4Z$9L3@4x4|^I>)5@A|5j|1ZDqTo0zR9}BPl=v=S=Yh7{Cz;FCjk_Vqo9nxndre@qVQ1 z2G0Vd{oX_DJ{|hI*oRBX7va<}0C${y_Rg{o>T<5Y$>D~ED;E{Tec)|Z;OKAz5GRKh z;NbA3MO5dVz-4Nj8orXJhH+JTgim*&5pcoPS0;IRnpdE4a~k@%d2N~zNW-`kjN`U- zf@g|tc4(?=ShO(t#lywOe-j#Q4hVRoaGmf@;m?GeP10Xa^cSLczITx9yr)O^$-+9} z6+%xh^>=08CVWHq2jL%uJfFh&J`=Ko(;gI_BrFn+7oH`YC%jqs9pU}LM}$uZpA)_( z{IjqJ(qy{4(nqWn&KF)STqV3sc$aXC@aMv`@OQ$Gg@K+*M_42*5l$7(5-t?pEcEnb zKPvkZ!e@l92;UaIC;YSUGhvR-=ME5#6xImm3Kt4ng|2X&@H@gE3)8~i3*Qs=#F8cH z+D|w}=$!+eCi^AA2H|7ECxpKj?i2n=_=zwNOo{0nAuJFM7M2Q66HXM)7B&c%2%CgA z3wd{j@!v1}k??WhZ-qG+TtA$I2tA*=?-w}RSxLNqH@PCA_3EvTZEbNOxmFb)y94Z_sJX<(JI9FIF zyjs{Oyk59cxK8-EaF;M6JSglC`Y}*4KLO#7c%1Mg;c($7;Y6XQSNvSr=L)YBE*35o zUN5{+c#Cj@(9=i0OZIl*d%}Z6+&}o6@JI-Y%>O`O4+w@Q5F*Rl5aT~xc!tpE8^`^M zTV(%%@Co5=p{HN`L)kwQb_n}J5H|T2mI^C`lZ00YuN5v6ri46izDEzVTN#QSr?ZV#+_X$50 zb_o06SO)WXlrSnBE<99!`c%2k7hWd3O4ua)rZ6SEL%2!k=~e%k?9U6+!ruz>Fu`U1 zP7n?i4i}CReqDHj@Mhud!pDSv686J_0pl$Yo+La~I8j(5TrRvrxJmeZ;RC{-3;!(4 zfsDs=dJ8>0>le!2AiPF+hwy3PZ-nHrjE9$Ch#}$0!ZU>ngh^qG@LR&Wgg+2ID%>vo zh42mG?}dL9=3`7^`o{`Oh0}!R3Kt5O2wR0~h2IhWK=_F83E?kj>=3Zjr@b?l&3{T+3B7gt*UgA2`D}QnGw-D=+n0#gZ ztlr)L7Na9>6;98$QRu=t3sxacbc?a-T)OxDM`=w}ev*fK7vs|TRz1*x^d4y{g;pN- zOuyYlD?2k5T=NHb-}}CFR*eC(<`R8{8~-U%iKnfq)6jl*&VK0XVQRWrfNemYnU9)X zAPmhu^XhA%)d%ZvvX8xb>R)r(vfh-nXW99vtN&)|AHnmxscM`O!fUjtIWPI31_e?# zj=toid6X=kuI%X>*WTA^5S9v`fzsgf2sR{eMFX=!?2BUVz-*U}b7FsT8vletRi+>~ zw^lYY7F-?0?hN)qp@+y_#CPW5yKGVEvV?1laIbJt8)#}6TwW@Ow+DJ#%DMiiTjf8ay(sZ4^w2zt+~(mPqoEMAfR)Vvg{FZ*oyxpS zJ!jTq>+6tvLAL!-xlPy|(e2jVFsg7eP0ySp^7ffghvS^;C$atXq`xBZVblA%K8fQI zZjB#1hO3W46LDvUcm!b^OK(~=h6vNDgRAd_DXaaMqg*IkB!yG_xtk&kvB*Cqu^;%Abb|cf^a4N09I|CkzsfUhCy&fC<5~YPS7>N|t_wo%BP~BmK}u+XJ~eT`2nX z>ZG549GYji3_8%vLCE0hi@5)nM5&Houk`ZYRQhNSkG>IBP9=2wBgA7YKq z`;j;B2eHAd{~HVb%moYMwP1EsvL{dzkJ1uk49f`uk0uX!h)6L(Ct^#XSeI1-f~5wq?3` z_6W>$^XyTW>E_vC?ED>W51~+BuL9AyM=%2RsX5~mM z?#E#+;ro?YDnGD1e-(!0CAJ-Q}{dKr@{^)^;I)| zGA|> zaFKAG@Lu5`gqP1xF6exK01}F)V8#6<@vGEVb zk`;fXR+KhyL%LvBe;cg0sDz^c+hM}7JZfwWwv0xfa?9Mw5u6V-u>@QHgynVwtU^hM z)$m8G0Y!+F0Aiio=Yl_Xz&?+5F!y;JaHzrqthn;t9DJDr`Y}YsJYcZ(GJLx?C)hd} z*!;)9r5&CYF~|XPdEFu({-Knt4!(J&kvVrqS%qM@fKe{3WxE2eLdC&eN*J}#ifJ`C zbHgIlAOvw1N=kG`&P=V37Q!?=g%c&7%CZO&z?nrVVVH@KQJ~c_cKaud(VCjQjnUIC zL4Ho#i%j}_KMK4Wh+cw`uzW9u_1B=_0C*ZMW?b51dJ2a-I&VZW9o~L?v8m($NQB## z13|``6r_%sI7IPle4aY3?)m3dosMj_!#3*+xtgBJ()!3#`g2LpzrZi@$(rXK13+1i zV2YY`Qh`=xaYv@d=QzU-H5zdH=pIB*zo=E*9BPUpn%Hm-qm*4;+$pXc!}Ig>+uY`# z;`nb`oZ(lvnYf29ElGub#CUU|=j{+##T~7n4n$epSwSQdn|J!lMm9ocd^8V7Q#&*B zoXyNSo0%6Oj`^W+6Pa;d&XPSseceiPe3jmtcQ8M6@5owSPS@}8ETxz$Gn35GY?z63V@p<>= zES`iA>Q1}|vL1nrM1jT(`m>H_&OjEJqZ*_`oQnD&x~I%g9wPgmgnu-QYERW&{=WY< z-`edBjI<8zpcn1Ck&OwL3@cGO#K@YR`kFu5yvv_9+BcCb3;gO4-u;fA!Il&%Z}@@4 zFP08a0da;MH?~-w#4j2@9Nqyf2K7cPhn5iZs|YG5Z0?`p#tgbt0op^vJvJ4%(;Z%R zl^=~iuyi>5hf{$EyPv^w`#T3w10Jawq7oXT z6|+zi6`89b0{@fUBJ(?(xD)|iL!rnTIIJQ`!x~0T?BorV=bmF!7J~ZbQ@-u)C|wmq zaO(6eXH8`Dhv}f5;S)zsOL=?(EK6!sw-~)DGcBz_`Q5C;{?jbg!4oXKn|DR=8bb1G zsq#}3uLM&YaniFH`isHiZh;Y;ZytGP#(@Q-sH*`XFmah`sNprq%w-G(cIe}OC>xWS zj;bS0yEI2F%k5QjsUI0F=U0U-&YXgWQSGxZh!nZniQGwBGGd+xN^D_MrYASL?LeEr> znC1~a&(jl`pScqX7`wL@J3hq`4#lh{j1M8A*)Y|()ALkkJ9cD_OO@xm&@qI!;R`{r zLeyi7x8b%$D;R20xcOkN17*Tr19_Vd`hzWhrt_+3CE?l%_na#5KeR@7L1EKZkTs^z zk%!A(bI`s6&ZpkoV%0R#5D#WRzI}OtiA92QX6oLk?X+&JC)gg-Y=Hhxll zJ?+_GcpQZl3nE}_GdNB%@u|}f6B90~OiN)&V}@72{LHcBiJ~q$H_1E;kr6#+o1ggu z?_;ShsK?;2zEH3VggP+ZpR;%zldplT2CnqY;u1Xx!fS>HCi%gcZ$SLE2Tp2CU(lGj zy3>AHWBTij`yR?#Yp`?uIHsu8XouDA1$pkm5ZY-Nli1laZONR@<_|VJ$8>>WH2-)C zv*(#q8$E|Aq9xA2G|xS^!W~y-dq|}9HTSy0CTg9X-SL&y*P14n_Wrup-ut-zHD}>t z725g~C$?hod+>8S90Jbkln;)9;up01*={acB@DF~kZ)f64jC_769$2Z<&Q|NaQ3-% z5jtYD=;XsOvf7x2lUns*hX;#=z~V8Nxqna&f2a)>N)0nXk>qYN0G zHXZ4J2jQ^sEYiShjA1k=eg-9?)19YGP;@91wRuP3RCY?%SBx1uo`cpDPtvY`kOK}hP$Eks+YK!|FDWQ(ZO(@o~aDe4!( zcgs6Sm-V?E2$~g0g5^5PWl`1ySbZTS+4qc)P}sa3wUFBkngG&%nQX1zu<1cA^vxNH~o2!+Nm2aRZU zH-cU5)0uiUs$XIaCG$NnF|-%kKH1)*?u0zV6>Hs&#u`B`3K5e(xbkH1#T^H8n-9)& za)YZsN1JNPkv|Sxf=uLNDwY4**F%6K z#nzoRcYFXXqxoP?a$57j9?4-yl!Pxt0ivks2$F>)5MZyfwQV|*@{dap(Y%==7oyp> zb1(iF41W=QCQ#-Bs^bu^i1|yB-@#D$UGvDa6TOR+Il4(A8Qg995 z324jZl1%0RWZi6?RL$FaXMO=UZ|&5|L+eQ|Om_eW#v!@ZXE6=NK)l7e8<>*sUKhgH zW-Kih&f`4RIMjvF;fq107)H8mFZKqyJGB&~i-UxP?)imoU8Q?X6&#|dg9seMyxqX2 zhPC|Zh+rGiwOx#Tq|NHsf}0P<79xHyE+^s#BiDTRgK?cT(YRJd_H?WqV`@AW4`E>W zx@+y0-7Qp*+Om#*-KPDxwhyl%XUcxG<6@`$ShumjKeW6cr|C@yTW2l)1@hRyQJneU zSic=eL5e80AbpZE^HIDd7{Z^%Co9M{Ab_!*6$QQOFw7fU0|_wK^EsWVLJIJo zPdC<~9S^FbtlEeh?$i7iEP1@dkK{Pz+|MW`FLIN8{LSTgT#YCPnM;E$-$6{Nz#S%{ zB&KGKfd-Vb9O@cMmySdbmN4ai9Bq%Aa-~C_c6NCE#qEKDL=xc}f-Pea3kCMY`<%x0 z4Lg3@BV~0trUJ*hWB0=wN0%6{Nrgt`R)*&~`R>&HJATu{9s8!+7_M_(9_k;Mn+(r( zdcixq!A}K3alItp4Go6(bM}vSuX@utXTKA_3zOM=|5?G-zUbS-J9zvUL?~}S+rT3p z)#cSwFU_$6ftxI!i}sGeGwOT@I+dzAx1D6l%NIAHzKehNJ>S)Sk`VlQp^Z#J)dVt|$*!dBqc)COiPty>L7PVSKu^*LQK7`@`{N|uqGV>6l$pAVGv)q2K$;WN{n>hw^*Y5n8 z{E!ctgx!UCU=`yEhoD9hAAycB#~)pK5>nlAB7%D374j0z*)twDw;C}J@9-x+!aS@o z1DP+k<1A=0YKpjlsPj=*d560*DD)J)U zg~I2?ca^j|wxR>^kplo4A0>xRM(52$9#_G;l@XA)V&o>t+>lRO<+uqta9fBN$7AV`Yn(25~Y?^zvf5=|(;NuYIJjUsj6mgeb;9q*0^S2Z< zMS1jgq5SOI^oH1Gqf`;6yb#q7o^Ud_{>kH!|JgaXjmeUo?{C}=EiUPdL(-}`4b_lvt=)S8@a8OYBWSy?Z%G+K{x`0oH#Y4)xugjGX0|L)t_onP}*MJ=d>N=gN8=4gTn8nS~`wDhYWOx}>!ot@4{o#kU?#qyn4 zfAGV}i*dpOzFD0RDsxc844-TD_~CM-*Nq=?$*?EtO@v-u8jBiFU)RgZC*@G0zLVcmi&<3bVg}Iy$Ez8Aj?$DeenASPeAytml z>r$bu?&zUQea>jO)S!6t;L1n%>YY%r6B`A+%uvIOOVMSE$Fh05v5{r+f8VjuR5um;`$<_orgDG>XClkqNeQ;F}ya5fI?F8j)KuKa?Whp!Ta;8)`R}_<{u|L^*V%Kvp8@_kwdNxM0#0>1rPG>2))=pX36F#_Bo9Gw{RKSy9WNTJG#xp zKdW2(`|f1>KsBu1%E0J?X!`-g2t9BZ)o}z5dO9Gy(sC4>NaNwg}^B;{!LTcCV}UBC`R&p)1|9YTWUq?sb*!`Q?bb z0)(Te6Q`)-Wdg0xt*c_b$*1ghjb4Uy5qH|`jrP~%oc5YjL?!>5@&$hQ@R?4>i8Vw4T z3pVcxBUo%IcsbOxc&o$W+YMcO8{z?Wa$<&W&$ImIh*T(rY;ck~8&z46Kvf1?_*{$O z({G@B8f^(+*K>?-Fb?-jvgCEr**l^A1k7!& zef)AQ$QHFiP^lZp#Wpf4J`Nq|&7)C7zVwScP&SXIphluUgk%t^KA8H1BnSUP_+re# zu>}Bk?kR>2;U5s6;in4v=@Bs(t?D?l4-Cdc2UANl%>bgIV!p~${8+aZM;TCwDag^_ z&*1z+z$3~|5p(b5<_y{G{t$Yq zuo$B7<^|QiP9b0Js=O-%^KzpiL%*st=yR9ZLq|9;d)>q*M%>} z(mWiPH>6@<=3G2QinOxbW^5@bE;o*l!Sn4Jtgu>n1@ z%Dsl$9`*1rmy_$|h=b=@n1dQCFynKLTf@UiH3(2=y8C4z_d4)L9wC{B+NgEMMUdV~ z1adDeaL?tD5^hM%b)gh|n_c1(Rc2L!9U@9@NhHnDp;ypaaE57>nb?ED#F0Gb`0PTU z7w2eM<0;M~p{crotxg|IxH_yh(#08csXCs;L^K?0J&7eyb7_ZhH#0C66tUKIU%q}2 z{`rF|3C16Cgce<%*kX!gAE{pY4HT9vxE77G5+p2!y%2>rVrtiVlg$xGY1#txH9EV= zeAe4Wfw@*9+zYkTf@G3S9eTA0>jR0+rl^gNgU}VIauU;76qtc_v>Zn4klOV$y8z7` z+I@brp~01FRvF5$3qVSsjcteNkj7=`&^~@%`s?%d{T!*7=3CyY*-o@`(EgVrP_SjM z-_UXuEJ&A`4L%@cu@Jy1q99LM33eO?QzmWW`U8z^?3#f*{t z1A}xbezV&P+SP(B)Xta+wK5d^)g%J>!IuAl+wd0??=FqesoQ)m6*j9;3HEIGwLcDr>o+;2Fv+QBVI+|8JXp_2+*nbAc`2vDU%x|2vRaU z3Z9E|j>*MXg0&_0w8SfDSeB0WBdk_~^eP1U8)fIxL+1nkh@L!Vb0|HZf!jYv&ldR1 zrsqW14^Phx$T7Gz>$4H#XJ}39i+DF%FG64$BH_O!d4fswIA=c?zvOFmtVBUFPwBje zfP*}>vye?vVM>{dJ~1-b!rI1CJ=dvfoDZ;`I%35iyha3ua(0{l5!7$T;J_JLIOIgK!C$JXl zoHh7Yo%tAJ8S1hc9i|w^pg2uA%Q@P#RlSfD$aipV5aMIA^J?|1jH3~24_xW7%VHh@s+5+XwIn2aE|ck0bk7J z|6}icpyRr#`(KT9;|$4=QSgw+VMyjjhgOQFAcrZ@plOgT*;ZoNk!{&l9QjZAsjXr} zF!6{u$w+n>34FM|jwvpLHYHwtKvQa(0H#TcDK<{51WJNQ0XvREffhVb{x}%o{3Cjw z?>Tq$#|e*iy|vz3>#gUN=+3?O+;jHXXYYOX-e;eEvaf+MTmBSN`)`4AlU}_R%3dDt zj)3ljYZUOnuLAT4wPzL^UjO^nZdI{D!zPguA=F6K&+-UV7 zXU|!==m?~=1%1OEkAn2HQd`S^j#%QmzU91Hu(>J?Wp*ga<-9~pOFFWQxK$UWS4ZQD zkIX-d(%~WlF+*-O0#G(mg+A~XuMY*Y|Nh#F*kxUUC1WSA86~;xY}pld@slaP%U_)G zH)_i6^anFM&?05KKOm=g8&6pbMwn`ZDQ3m3ddELL zVUa7H&AC~X`K4EnM*T zd-&~)knL1_Sld0^^orzJZr33;#_v|Yk*h&|+bTD)I#r~CWi1VL6J>KD!1ve==C=Wd zte{M!h<67GuZdMX%wNV++rtQUCev$|f4%3Qmn#om4I=s{x(7!7oBjJac=;{;OMpq4 z)}HtJ>Uh-0d>yjzO&(;|!0a|@cjCwgu zMcnq=GwW26-)G|gGRihF(_K00-K+8gPt#gIbCbNjeN0UW&pbxYv~Z4gPcsRs$ujM2 zr4vk7G5)VHnMi~N_&;5aA?GLcUn#}faDbYqG3F|3pkL2mjQ$cqRTq?B)nvisE{f(oRuSk z-s@IVAP@87kEQ~A{Pufp>T_P5gZT9D< z{Oj7ROPo40lvq#6HY*{YMM7Ggyc1{G+ZaJP^|KV~lD@;&jeh3K=2F>DtWXU+HDNpv zYfybCW`w|eibVD6416={^48~K^aPbJ=7$B6I^Cp$)nyCngP(Rc%iXsp->b!Y7M@QAbX*|1pOLI zV2enhgDRBKXf_xz?x4+hl(#TaM5WT8*q2bI=9AFmJpF3>X-{>|L~F8CE- zKNbErb3X-srj$^*#<+p9QQJF!Xgv_8a^5E=l>H;q>@@~$eXemr*+0ow7fdSqDJlE- z9dhRu3TXKaAR=X+ou(g5>ie1L`aTs$5L!sUs23{p6Q)6iN~NGg0kAGK5unudCRT$q zO!0rRJWnzR51ABrmWlaU>nG+&lTT>vEfwl9ej;j@FOq&XYA!FYl*pDw4y5|pWM_h)oT4d8Gb&W@41yjuLg%+ z$rX-Sj6fRHG3wdF%ffbI<=yH4>nUnyyMCh{j(ao9+xR^x-?b+5yBdtq;4;2)YIPyq z_xSa_$Jh3jfArhruZuUuK5}0O7gwz}?dwZ7uaB5fL-=mzMl-KJK71U+utjcoL5u z`m1B+>e`@iyBD;32Elt{iV*iUDy5GZ|3fHDzYYW47ZSafymqa5VcnX8Q~0$4gaGhq zzVHDe*4Kt0sOc#Ul3m~)$~F3(w3-eIpY(!7-q^Nj^gVK{&|j&u!kayRROMeq&lXjx z?U)I$3ENf&o%^q_NA#rQ9xo`I#e(eZYRKG}@i*GGy1wQGi){~ArONMu<|_K)L|eZV zi6G4O17y+?MA2yR7dhcyPt^(V2=0O&(7Gxk6s}8^zYnp6^3ct%ZhRNVZhdk0MY3`n2xo1`+{S`6ST+sGO&kSb9{^Eavl|=c!7^R(r z-!Y^$&fEN|2!BD8T@)`!ElmuaUpkTari77M5OrkgYd=MN_yJdvcSOQ+s_^^5WBGXf}wXV^A~MAHaB|AV<+9?_SCt`jyjKHK?-pkr6(>4 zVl{_f%q@y-`IJB!m}!nMiMu@`k1yyyzP5ktX_{H?m~!m1JJ}UhIG_Ds10R|4_+umE zTTYJsNNkD*^vL9!@&-tM8oy0>r-c%yEncsN%1Td6EBMYNY{~a?b_ET*c?h}O%8OY#Q|D@n+XuPw`w0FN{3{h3)I0iF!V;0jRNNT zT|7jwYmqYnHMW+H%6?GL19soTUS+Pv<6YulD;&1#U|vBwAE>fWT^4w3)u;HrzxXXy zSV8-4>UC&8epZU##{lK%LytMPcZH5>*qIq0{snpx(5#>Hyxr9&mBI}hu=KO67`l0q zUj!@G|J{G5*O0k0@(dm`Sz80gz)YW#7ywOwPd5W-A^esKwTfDYI+vz~lnPpb8+xF6&i5LUik_AC zu)~r_@&c2&kYj0^i{}&K_!WKN29mdFnj}2?J_bioVU3J!CL}oLZ{fZ|p_c{TSN+=N zZf|fcUo`^IZt4OcEdt7tv=OdsG7hqLRpuYJ%$%hJiUvJvZm#;PL!4gCc_5*t= zzWrHgLe3*EbP6}4Co%NE1ptzdogS(4ko6 zNku#m5qhb=BuxzhbI$i6%6?$BTvx0i;J3!)C$RQ&v7N=*9TrzErUJB|i8yz#t@yyq zXSO*?u#`GnfLL-Fy?o?(-Em zAVJk*G9R^@+HX;4HU0^6{uHqVrLBj$`WKq6v$T^}WXj@@8iql%dpa8rG$Bw>F8P)q za~K3zOyc6KcHIw>pJI%=A)~G!^CBQ6{WYSkZhyebDNdqqK-rVJ{N-N5EPf~|0=Xm1 z1>S6#a*gJ}`jecLg=2i+LfXog@)wO4-oCK(Kr{rWxCiR5^(3Tw1X}|Rh^yIuR51i8qArtT#EB=BPHg>|b+}soK20m*MAeRON17O@H%|#-8 z@vHS8@uXZ3Q{u0tYc1tZXkYl0{f})&5#QiOo;VqNszfZS6d#TBs0F-e`e=e>vwiRBq=5SY7DPgUE$x{p}}QP-T|7)VBhv%h_JtK z1zJeye(wl^QfHo#LZKSJ1=XgZ0lYM@^Si>LEzFu2hLY52n;@c)&KB>}tc3rf;$D=L zh>^$4Zp)zxtw}VQXUqo6g`Qoh3wk~vo5iqfJ}(yXpSigv$kbXcbOJ|QDAyT1V+s+& zC2r@W8nZZKR-~-Dmw@voBA{>saf|Nhcv#|!8I&Eqf8Z}pBcFivjQEfq`k%beB*k`1 z22M`!9P_iQm3$e*_fivQOlJ+kDLGZ%n?`Y$UKM{O{fe?lNWQZ)Wjm(o{4bCXD2pcHLbF}_&m_uV?#0#r)kD0@R^Hp<@ z*hx*AKg7PsxVt9pUAy1PXTKF&UDJbaFx8NG3X+)17cue4Vz2lZWKT2|W-(o6rEWoK z)S>8B3N`UevuMg-cC3kx&JSmqfy7GUj;+Ee1z<3>ih*P{oggVj@$GgL?MCg&dZ+f- z_9HqgG3QI1|IW%y>|6IWW7ty}!?bBdNOmD4HC_|rmoEOQ{9YcO;h)plp9=EH;M$<4 zF;fVt%4cEAPqF82eJU-zW3Nq2fl$ipZrEM+xC_zh*VJg?$W0+EZ)wQ`8EnhmVK0?f zm4PHOUeAdF*rrlfrz&-a5NOVjGFAaw?=&W%O!7J@3EfTKXiZt+4XRSI5t);~9$QJzS33j4VeV zqN+ZfZwMt?VKSTS^PKs5mOO(;ADTFw{AIG2@pxbQA9?;~RI96Y#=7-G#;n(WzgOKL zkA^wzT5D{3c;T2#zPepDH%9fmwBMwN-o3nB z9=Pq0D?p0!8&u>-N?&W5T^bDA@c8L{=4(0gd}W#}G+^Q~YsI&{joyfI5&KeI_u1y1 z27otqH?`>>C<#d<=R$mnTYx)oQ9%lH6Kb98>s}q~vaK(hHckXRyCGCKfJ(c$fKa*0 z&^a=3O*5idsTzDcc(wq}Hjnx7`fta# z8QIBLC(JTg+~hm1)P49xd^o8)r!Y2jq??*uM0@Goo+m&IqSdjaD{C?EQUeP_tbOk!lMv+vtAt8V_uXH{-#DjEwZaU2X_b5)pU! zyg$VyoTULd1vFbJ@8@S#wxP*rWhp#hZ$!Y}FNpfG`a=v5;vEA9n*>y(2&v+-Ir0SU zYjm4u^0txC+M_&<;eQ&a@@LdP$W6bo5xR45D#wQ}_1xx(pQ1p~=cFd(q?#bU)UZlU z^+|sY0pl`pILy$+&KY?PQ?`su6nkHTz< z)-FKDA|a{3mojp=g(pZUK4L?vnZzoA+wtKyh;_nPip=HB{g-2;{~CC}8yL+NQxgoWrLM~(LNO1}2< zdycKV`&!u$++omH0>?%;SAOdNN>rViVvswO(Ry@amog?sJr;~VP2K1CM=;qDw_b@ zXanoxJCs~8#G)A#q_!cnPOtQUXD%wY@LuuwU7Fk{Kf6=_!drpNQG)VEX6pf;F{WLR zr)n`xDD7d5j858IRz3x1XsYR2wu-`epLNH73X)5LeRu5Rg9$^vdicsZ$IVi%aGT5NkVmNXKm^iQI=5Cp%ut z&K|Y&0ufrB{$&jVRVy8=uh&lbYN0QjOz64Yq6eB3QzU5?$$T})lpvah^UaE?@-L{< z+AqUyI;j;0_;GWj{=v=fM%8bR2M;h*x(BHI$bJCSY~Q}QhA|Rpz`0H3f2PdoBYHk| z;`EWRL#H1rZ>&7(E}u9ZzU?YM`n)|0xXN9AszZeBe6RFQBx?rH*ygvG$AY<$GvuGb zoZAOp@I9X$iL)87nrZkP58q#V&^-?Q`Ewr1Jx7n^#ZPKV7@S?H*0bvj<6iY#)(~^g z6`%3Fd#O22san!5jLUy~<-iLg&u>ne7lI{`Gwg$LtxNJ=UU}g!jGrL*br_t?VDjG1 z6%+~QZgP;R>|%#Q4a*5&ILUHJ=p|elMaJ0&-lwEC{3c=+#>@xTn;TiGOU8#+BL$y# zYNhgw)>3`dfNVrXzuC!`Od7I0weuuMhN-o}M);skA5bwC8FS?9>2rXt4L_3EGVE zt}@Yt_8Y6x>_SOLkM0kcz_iNsorJ5Ye!W z;y)cfQb9+2_-sv2PBH<~Rz5b1QdFZ~$c9?~!T=BJUVCpA$R8(+MSeZ8EX0^^dBP+fs-eJ_bIp{R{ulu%QNVsItsv74ZL6$E7@r20kF3Z zLaeof%dS}mU4>lCqD)~ycr&w*7nsy1}@qZKbISI-V=J zaF2sZ+#*u+&z56kRm@ca+?KXjvRsg&zjZ9W$XcS#^1n-7I=!Lvvl&xp3y!Fuc)*K@ z(n153{!CC>;>NHA2jo;rJBIfnKCGrt~58v{#8MC zp7x-hdw<0!DYo7Y+M}RDFGs#_<}2#5cIfKKp?lO{=*COy4gWXCD^XqqX0#E{;!|qe z0E){;716#X7J6qL&zgm)5TX9U7?@HTt@7mvH@QsU{zZkoWFY)TNH6Ok4HwhR`=jQT zn$gw--=nX~F_$;XE7=FkqGXtUfOR`7NV@(obO~t7o0T5brZsJrXNKNx4$gVVJb4EF z`-QmIkd2${xt42BVg)J+>EO;#{yKT7{cKWy6dT>*=1D;clQf!}6?c^PJH8>`TBG@3 zjk#J87cH!Ezn1icM&?3nqzW>lLqPJRB`wYD3oIP(3F zP+6LxCp=0+Labkt?L#yY{B9*M@CpxG!5gd&mts~0Lx^J21tLNB$y?`;G z)x-x_Yy3B$OIbBC9pt|PW0;#VmW@MyqTIl0k+>!KqFB?mBjxlT)3i`r%&X$BD!7{Z zUiiB8DG`2!N%q+NL{340PwvvIUFqGrke`@~vgtUP&avxEA`}vs==4+@;-`NCw1Ls0qqEJyW^;%*rLZy|NCA-RXi@J7G41RCoB0&;XGsCb3`CaMk zP9S4iCpdR@hM;K=w{7$>QMDB5%CwVgp)PQ{WZ+RXs%eLgshjb;r!97;!-<&&TzF83VfIJql zu=?WNcG?l-to$n-K?Qm7;cbG{P3q=4&B{9|#eOXo5b3>cIBo(PDCw_MJ|l}{6mXli zwbran4Q&dgFgSJW>AEy+e)MNGFDI!C1eu7Okc@{-C%#06z*b$lKdPh`diDpw#Bz$+VUWd=GuMLN?LW*-N;@QXP+GP)xn0(|R z##j?+%B)Tet(&C58mg=exFfsEsh}qEEHpepcE63@QfJUxjc4giY1yXGTUzwy7{$`t zyx&4^b`@iS%6<>>N(ETJA(c&)m#;%_-wNq1UG^CyrP8yMaiQk%siPTEhDhQ8$VVs! zKTR6luR;N%nt^aiMy=6Zr4jlKdDW)vTmZ)vnqj= zRA_gaV;$D`SNPRtCVLEHrkSkvF&t3uF}e9h(a+K5>%8K<$N*2P^|b@rOA71@!}=V& zGHUzS-%3(4f3@;rE1aUm-=N5fOrKIqZwP(obfc3=_5-3jX6K3!Pj{g}Y}G>|nBBZf z$!^HGh2B=pc?eXI{w_cG$L0heQR2%`APfoJACWD6!Jh?9rd*K_7- z#^fVxH|pbQ+o&huD{jfCdUGCiHqu}!r!Yoo4Vc#zUg9cmhP?Q-qbiP)dMAG+l1k4g zSc1|CYZxG3&(v>FQ;4Mi!t<%a3R2oifM0}K;N9zM)u;*g5G!jvu+=C@lmH;hO)|)q zs5uNItE^|u4!pk+47PKHvw+2LXGQfYulOGT)ku(0)4)fmR}q|2>tsRImR^dO%qLjr zEVAKYyl@Gz25&LnF^6%qwtBg54O)d|=T!s0f$^>!C=*M8`(}B78NV_hDBn4$@lNL> z@m>2%_xC^oZYT{S3@Rvnf9@ zlSIbf9{Ya9kazxiiZ_-YmHNBa`i~v`Hu6Qgza;8kU*oUU91`CxanTD8yRon2wQ+AAJmKR~+pw{)wH zZB=PIVwou;HZdQ&{9 za+>mW@!|hN)hHO9cB80KaBx6gr5Rweu6dp}IL{=Mx>AlSjTJLeDaif{cX&*Lv1Hq$h->^LD@};&E z%X1zAxVqfoQ9jmq4ZhQy1od@0OHDHh;=!a9zRy|VTQ_*VImwHGisY>;KBv*+<63>J zp$XX){I&C{10t<8=Tac80$fv~=rC+=SYgj@=#|0B4n5}p+W8Iqq!^O4+o|lvpDBwR zT#QQKeSMOf=Fx18@k9e1`YK55K)?b(Y?7beWTWU(r77b-SL4rUz*LXY<0QnEw&O2< zyCW#3EUAHbg^c%Cp>--9&4qXzv?DG$r7h3It+cCUbnD2ECxzSzqKbS+c23M#b&Nlh zif>5t22`Wo$E}b%bNnSGQXENl`cM>90ZAQgWz5OK%wWL_rq#PERhU^ika6j}{hYSQrCuk9LBKKxZH=tCw< zr#*IX=k)up?sVnfZ_9s7<%ypr=3^38)RNxm&{P(AiW1#>!g3h*mR-BEuum zYFBt|53e2JwI#f^>8fKWR7Xf3VRY%-CfKoYO?Tg4Fs=}2zcZG3h+We6_j<^5?es_E zLO77M`}CZZno!m{(}cCLVe5H1>Rfdz9wVdp{mLkQvrcQe`D?^YXd_%0s=Co5srcq& z$PKPHhu^FWzj1Fm?3)uuoIl{`{z{GRZKvMq1Fl8t>E=2F!9ab=q$o?J`JM4Q!)5TG z>#wW9WE0I>T(_r}I!v_C*EZx4gx;u=8Sh1r3kH=8IoU~7n^&;=Zvrn^BG!_*$*ay$ zq6g%63%P2xha(TrxVzH*6As3$ys`ukD!?0A$p8R7#^|v`5T*G_>~9~>HJ-iVG1}G` z_uFUQ4m|=&d3L&xH{GPflFNb&Q$SaXY2=@~a58h2@|<*QEv}gEXvpEMX``wh)j_@z zruk8im!vLG<>8vG)7}ewOPx8YLLGNdgdnK zU&gUReq?0-K#jS4902hoyV-QH!ho$#Kp619m)|Rm3x0QwmZexT8Vg578Uhzd0I^#$ zbAH~xh^Wb<_0Pq(SzpCwk7d}vTlSf-;OW6=?m&F|-%>~JiJ{A&AzK|J;plF|pD`#K z?uG7HfrL8xppss$8^CRE?wMjggJ4@)KnCuK?>nb{-<96rGT~4EzJu={DQ4)1HO+2n zQR1cpz|mRhla7NCG)_mOa~r%016GPaq$&{_XKr=Yok+k)WbK(B>$Tv(jds<*hp&Ks zWp5#x4=G)PHPpy(HIgCgwocjeE<8F*w*;2Hy>Kv$g|qpM>UyA|p5QF}s^oBv0ijt|#My zRfk`#KS^+%1O!Aai4)4+N!q+Yw0(o4?Tyg%MrgZ*>kZ)tlaf?#+Uy%iQdM?zf2AJx zoh0xLp(HI(x|914Bhvc*gTge^%UJX(WlHhlYS+=Azgljm&k3>*wwYfC?QC~DNg(Ej z5B!(MaMYQr6$+dVI&Rll5kb#cF|*J!3-e}GySci@T-{;T$+NnX3YssE-&x7~rF|*j zF!H^i%WzIEsMAhqHlDp1w=ZwH+j&$Yxx7(w8PLKh$RVpbTropPF;aGVlw?Nlm+u6o zbviLDv3Zh4G4QBwGb#HDgd-{zW=$27tdc~p2RzY&m7Ekx@w->gB&^W9N5)4zWo)gA z?|6W})?S2iVBgO8unpeg7tP0P<^&f?#lF%D0lckYc1v>)mL?^r)lzg(o*&44QZ}~% zbQam%g4WkIq;bFlbwNco+j)O5pbD8GQYz)Qu@T7m9idvn!|0jvxnrt)M*kPzk-K|R zK8JESWEe-B>T)Qb5zJ!HP&AK&03Xquxjbn5K-C$tS$oYw*(^!B{IQB`exFVmd7qQ5 z>!G*x&|MGL_tBFc&cOTMqJvN>>&pto7Snv$lYXD0{OMn^6CiiGSdZkjQhBqL$}NDm zEFhR_saD1&MH&6!ur@ufJf0?xc}+OBTNZC#-ohp>gpB4pDfW!f*O`5*=7o}0_Swpo z;?Fd4fU~^yP(Na zpGW3Pw}$lMxBbe=zi#d`VW;)YW_c5o)u2|N0TVOE>q1o(xCP9mfm`QX7Pys4C+j&p z5ung;*BtB&7>v$|N}OPIWMOwWGb6ktmqvm8d&~#_thtDg4qzPl62B*T?KkF!bH3k9 z!W=sv^doYk=8XN~O%wBh_M)q-J>Rj9K1Gd9Z9nRLN<0VGR1{!^#xfu5aQIMiyy(>V zp!8H1`0V$uN%+?(Z`f2XfED9Z)kqDhG8OQ1krSK zf29)ls!6X@nrkODNcu06xWnt%{EqmY-*TCZf{wqa29|ywUp0P>Fh`KIUJmK0fy-(Y z;`2CgTYFY2EK1`l*9ljh0^h?`)DEx!Oo!<(%={vxA)g&^GBG zJ&*1tLd`UYX=_Yl^=u?xYVZ;o$8A=lI{ev4xkliut7nxJ2V&!vs683w+2S|ERnn?8 zhE9MBa7W^O{(`)Jxp~fSs(&%QZ3Ddkyde3Wz`GU@JzDGi%;{Su)x^_7?*z&HmD#a! zlB}~$DhJ34vschS6Vl{^V55&kdf3t%nxk(gB@w64cBQXyGHm*{_@US;<`uPu*Xw_% z1%Kp@uhPvPBm4iG>(t28TCyG*?JeCe@7&ZBQLR14uk9K8 zobxZiDPo)1&DVI~Aw8&VptahQ>D)FPi*ZsuZN(U(F_-c)#|w*EC%d3CSDJfjyy6de zEq76!xGspB`;w&vZkrz8&~tosPdNoSoZ-)N^pF7uEgHU%9_ln`@sW>-9_SP(Nn7xEsuLG+ z1VaRyrTb|yNB&lAT8csh%PE_!P^gH&q4}D%3eC^1G!Iyqs6J64fmnE`+$bH>xN^0^ zUL*jA3@X8rHz}_$Fu$f^;cn+5KS4s!oKi8U8ZYFu2QYWA_$=?`$QAcT!>&jvNStdD)f#5g!!B;5z9A`p`E3j`a3sba zstjdaIFx@X&SpM$p?+pIDS&Y+u|dCAQuFo{QjUQsEyvW`K>knO0l)QW6)ZJ z5C1xn&!zaN(O;lZ)$&Fiqbi?5Qu4h+``Q)UYT;n$v_oY=7U@Is)8VUC=HjjiHpj*3 z_H3jSmKiP)F}@vk0GTBE(VSt*!De2Q8VG8dWcSeiL~Qz3g!}*msZ#!&@xo2`Ol!2- z7#ny(&DwLEEVFm$1k8TUQ=x39GN5w+=7brd0cRm+C79|8RXg^K(sn29ZlwK!Teq6R z>{QeK_&jmX*zVANAmln~j}ZcU+9+vNlEL{w!mhiW!C$~q$ByQzaHzRWS;{S}Y^`*P zl@w|CJ?DAF!@Sr2Hgc6a0YGFq3~rL|0OTf<)MTA(5O9W(U~r@YgEbs>3JB)JbKTJssMDMuLq#O&fKVz92`y(=w8_U5P1s zDoi;kHK-!ny?V;QpFGH{TeF-h!&63iz>1rMPS3<_lX6stUnTSi``%|ibNXeSOMktT zyX%jiB?049y#B|mg4U0MCKuB6yzeXBZyAI@qeg5D*h7e@_}{@Rrx$q2rky)7G{YPL z0X4?c_Rp&ae$v@@7@5greannWcjUQj!&V+0x|m-z6rWb#W#itxe0$}sk~42h&n z+jM`vXPA{z!07{ebda6kpHQ9(iThOR<$p>CBX6RMz?Uf}Z1Rd&(aU=T8L2`RLVfs}Nq_(rCinu>sIA2?pVRiD$(AbYNVF`fkVjN!Bj*We$8a*K*G z9AGsmr>KdUsL(z|PGu`{N*kf`wAM1&OZ6FKNrlOqOe5ppVlq(@E1LXe@OiT)!~5U+3e=PW7Eaf!24#9 zKQP*A4bY%%=&h!;ajn0paow$ll#b49YV13k={20|S~H`qb{;6*U!z5*33{R7(N>G; zzPD*MUKt~MiJL`DYo5ltSDP2(cR$kiUfzc8uO-nS5x1~hXOir?*gJ;gCSdF9en0HVV`HH{uVsvMGbe`R{Haais?i$@C z<%%TTCE+gCq8*)=c6UzcoM#;gqw}12K@%l$;Qi%58XXIx}-yH!h1Uyum%SjgQ@+@Vo~v_6|LF zG3+5d;Sj}<{aHN^6An9+B0Q<*A77_@-<)F*EW&GZJh1hl9l?0%$`O`mMS-?(##!DT zlq@U+-pB3ML!`rBD%;RZ9KUlb#fuyuq)@8M*}~tdT8saLoUtfHEEExDk~=NJ16Pa3 z!QV#;Nc~D7Kss!O1y;W3d6#8V2=xwXT}1-FlPDl(XjSItqGqA9 zfvk)E+8qso;{;_}n8w=T!(Wvc&~zbfn6?oZ9YNbyU!g`F2c%-uOkFEFSgj4d>0K7| zr+Zi6NaFeMx?YDk;y7EXChiVn}Iq0p*uI;hjETpDC>JUCo=k!OIMhN76Hr zU)kw5S9}9ZmjUBjYKjytTHt$%4ygr}=EB)t@#viW;jydK*$70$M7_Cc;K;~BqgAT< zJ`vnNa%6u&8xhEJn>P7b3`NSmFxjtk&k z-8V)5b@EEvZa4B-p>H3}O=#YV8^RS`^K~*ARJmz7jB(q~A-%tvb1e7rpf+8^%*&Pe z$H9x#STyh}^Kx!%P}%WgOdzIQf7ED+HW- zx%ezqBn4fNy;ES@_rIYE`+ltWEE~p@-6t0ASMx6$Z`)gAWz4T=Ibj~eqSx-Kx;f+Z z--~biI-fS6+14L6?2Z2dce(Ekz7I&A9c&P!Kr=mG`uV{;()~p~{O;0AGYfNcqHJ!A z^Q2k9k}pD3H8`=N?mT$Y^ci!p+^S=vwgm-M#b~84*A$g63i}8TDEwwWX zH;>MkN!4J(^Sx>k`WDy$KEjhKNAcB#?$IhHmMX2q&1wFSN7fN^h9LQ6lSrQ-kJU4g zabl@IOD^ct(hAe3#5EO;`BC^8wxMJ6Dg3E{nF7BMC7J%);ExD?G1zZ~-xK`ae;fXD z^)cY z4WF+J2*`{E*L&q&$n^|)Bf@Q9Mm{h;!@P9ZW)R~%?b7&J40mm?^p&B7%!*(z_a5_d ze8=xGG(;`)4b5;^(<`N?y_H}5doZIUpD zr}1O%)TX3AlP+K29@B9iy&+dU^lRI{+;bo1eRCv!+g}LHWiR*Kjn7SiKXvc zC(TFMBLm1RVkXASg=2rmV3^Z_P(75!YB3;>r7KI9dhR zw5a$J4=e>E$W+df{PGjpbg6RK{9{L^wI96SBm3XC&5z1DX~#Tb9=5r}%yZWMtnlyu zPe1>kqaTJ8+5Z0s{b*8eME=BgNH9W@=)woA{7J-jXy2#g4`o_9PrS?>q}^6J6gAI5 zvG81$L+8J3B~dey=uz{7(zl|yU*GU7`e3%8kclk(&504!B=6ImnQ6#o)@!#7$fFra4lswJB$d&qi}|Q0KKC7aO_=EHs)ER<3D@mKbp|9!j(w&XqZVWU$I#**-)|E81jvTMAci~Y~>jk;?WfORz|+fuabaMu4tgkl@V|g`d4nO z@J=*gmMwthIIo2Ye}=!z^WVk3BcvT;Cb9Z1!!9HWjRnD)sCh;`5d!Le32x?(eX-pEs6FjRcph@ZI9XqNhkcAkOU`rVvGMSEQ%gG_Jir;7qGZICR7#9 zGYIOWlw_;YvNwFiofL*nf|{V^it74T@rp%DsRsR%;H$KO%451ch(#a_{%z zJ1!9(A1&8%VU!)wFN&6*0k6~M(+Ym+ZiW7TX{U7P|1dCTOHW$*?}D&bK>y&SF?VtN zHU&V$hY#`Bh+9+)?M879V!o_TH)qFh+hj}q34eb#y-MWxEKkz9|@ zm#09#6j!FJ64>dg6RUMyN(2HaruoHy5`Y-&AuCtKn)S~u-LJsikyAXvSyd}@gsYfe z*Hn0QE=3$R;eCxBNG-b~{R+R9)7Exg`4MMkX`5wAD^YJ#Y|7h?o+V$Ti%?0qm8jG) zoHDFLy$!{d8{a4@?ACXD>}cyE#&d7fB8yz zI+D&o4Xz2guDOeR5N`w=T~E<6VI_T4oSG;w_wjtGf8nwf;TN3w$`k89%9id==@aGf z)>WCGB&b8@ce3KJRRp3Pqrs|3;oMvA*RWY}%}8wJw@+rCp*J%OdsOp-Vk?^;NBMYI zxKRn4mgh|rQA9cNtMY#2q0M*mRArRYXJY=TydV1ny?5}?&+=MG);d2Q$60!u&_xiC zuo<7+Q`QUhwEQv@H}ykX>)+nrvI9)GtM9T?MD<8WKi0Qi~eHufPl&G*Tl^`#0D5H#7}hI_H=vSNuDSya25B zF7`S0Y!CV0Assf58V>v(_$k}<`*<)Te%nqiL=5k>_oYL1I@8{k9rffe+{kO^<-T?; zq@pTCv$oIWOL(GRk?$OSxf0bAJ9>hq^^|DpBfkV)a`v{ZSkADg_`k;DMi|^{O9lDQ zt~w5z^MCY6`H2_p2VEc`d|&^>1aXBxS8w_A!W+a_<#~{U$_Ymc1h_-mE_=nQ7HR0w z(hV~L>l3}h-a1g(5)Sr~I4Jj~Pr_G$J8OAm#fwoh_SZ@ts_!T20gt*D>DlMYgYD@f ze5+7d`@(iEtT`+cAu&eSt`ak;Sf{+8-LLmis{DH}P=ITC6;9t=Y~(LuQZOjxL_LB*}$6k^^c!> z-7o#TC;W*7fbBXEd5b_r2Pv{7hvWm!&j}Mr1}*_t5Ucfb!K#QkpGhIbf+=We@r#Wl zbZ?C8OWsa}I0XrJ=^6MYXwbdr?Q>jLGN|9KJ+2MLLYim#7eb$P&bL*mNzGdAUaK7}}o7d@1{g_-rbW>DlPxVe}dp zY=vonbNjT0x1yU)d+NO(Bb4Gj9+kB5tQ(r?iVwd}GczF#ob2bf<@*@cZVE)vgh)4< zxA^YQZ{$&ojr+t}n}hX_gi*FExR@6w#hCWNb->U`C>i}|kKes3wwqE^DOOBs@qwkT>Rqv| zJdNMY5{tHkVXuO(&tRP3Pf-D{jrThe}LanBRe%708<|2%+K6c zIghW0eBSmPlFpmH40YR)aY>sEy0F_!1yB7Ot(mK0@XvmJ+2FyHq<{iN5qWy;MBc6U zi)yW;vSJI?&=-$?Y!`oz->JW2hro!XjP3c|+zTZlFoaO`_WU-U_=!eye))^^*62(} zS%Uc*%0vwb8lf3x$nsgdt<|LIydeAuUlIloa_vL_0_zzxw0#xKMM?4K~z2 zOs1UY99pQf$Ni%<}96RlWpR<1`HmIl{H3fF_xz7yge7Mz0Q zmY}0GOk^K)+{f8EWFD7E+k#I$P zK`#s9RZxtZHO&Gd51m;=YeD9{wm~yijo_a=(9E{CBw=0*dS37%ztM44U7SE;Ay}J^ zJjmGRgFad&kN(PxxjsqzW1oH+UkKWLPZDxN$J;UYtmiP z?oy}Ame{SY%E*Y{*23S>YWh}HYK|1<3-rXhE5};4rmtBODg`9{LI^cN`!@WLxwB%9 z+d$Q6{9u7G-x@mWUj&uATV6AC)_uA)t%;z2MkI)R*k9NfbiHv#!@_Ltd+{Ax1p)_j zh1hIOUempz@|#}8c+KG>jA-tcgS8|Sm?A$+4ckIuxnCBax5pV~{Y5FK=!f(9yom)t zj)eauI&I*6`ScT}HDxx{qK!FgVNq)AzeFY%V048e+^TVZC->oEW2@kx3svP!(o`nw z0hj8c{B@Ye`g6kgAP^dkM&YfU%x=qwwYViZp<~f(n59JX<%{N}(?_e9*9132%py#H zN-S6Xx0MFeEN5$k`Cd4m%ym&Ha1*&de;H)&Gn-Ol_xP=;u~WAFmCLoCJwf}BMopp7 zUlcv?lWIE0zJR5UQ;2?B&gzV1x6#(9kc)D3?OK};l)d<@;@11E3D(c*TT{zW6c?qI z2FsI9DH;3jbbl8!fAu2m=Md?snI~t2RbNBXLE_48ww;WRzjthhBNOp2LLgDfMG6~n z5e91`#2MlryeaKpS7%NQwM?%+XdO2Pl!G}NIs9snIL)`o+&P061>TSSt33Zrrrk3& zBhRzT!}R=Rl{vNL;UN2C6(WZYOEPAN=iiX{oU?z;!ST6D#!>5kh^6mkLE^JuDv3<1 zMq#K%&d-aEx=5cwwV}RQluhQA)(##pOKZpWO~UW^FU3kZ4JiPPY#(jV1_CYRuc-?X zzJJ;146%tn-)kS)?++?<3kODdLw_D5M)CdTzH2h+!fOAVT0m0zoc8B=Y#f^Jk#@mfp`CpmskE}6Fi&jxK5il2Cl%-yrMomyWym+4 zz0;Al`h14`2zuTf$sHV=IB!}_or4w;9hx7!KazW3@Vwkr(V;h(v5NlE|6?!kPW!PR z8$5^nM?92?n(P<(kupyJThQ|sYApU!`9pMgXRs*39_-*x)p>x*&0|5(x<9`oNZWqw z`LRbP`@*`MQi_j#Wx~G|^+9AZL!|<17<9-fF7&x8*gUdwP4V5%z3H4Bqs5+eJw=Cj0TR zFHHM>dFL`Gfq5;mu0v642hVLZ*br5R*zCa^4{MjT~d-R{~+n|1wJ#$d&dqqdXpiS_Ls8d`982m#EJC5;3^S%8i%C0 z%8L*Glt&N++2hmx{5mqsje57MFccT_*NBk3H0!{R#drAnnBL6f6y$%^97eFmGa5iq z#o#s5@GpXtRS_Nf)8P6@?gz+&cFBWhD)`HQmD6zXX)_^_Vri571h`5|3X^;oQv9L$ zL2++DS+*1NChF(Yl1;1!fek5~Hf&XCRaZuGPY(XTio3q((7%}J)?4D09@gqb*k5@vFzaJo312cu=uu!vck`+VYQ&Y^RRnf1|%+ ze=}`7-1{$0dH>JU8?C4=?)Ch_@ihh4t+2jfTc7^=^F0@P?)U{PW&DMCe|BZN_A!-d zA(KX<@z_kh>@%mg*zJ*@#%bZjH;rCu0v+2-WT9VN>G8Vv6U(@eA=eiJ$TxQH6W@0im&6tr=lryq!Kr+A3`} z3-Wd=SkQIFjJ^~U;8dcZJ!%#;1s!K|>EOiKpyMQ`hIwXDXV5h>iq;<`&yj+!7qyw? z?T+#x{7Ly$da4up>!TZeaw}wx?qJhAOe3RT9;9|Syve_T9aK&J(!Aei zH?<%p8+k5$ZNm)P9T=R1j=-b)Cz3g()8@zKoe(v1!;} z*(S9W)7V*}RH%d)9T0|ABs#-ux32UGXzj)ge*rrPe!?>-B}F-_U;>&Aa8-UtX(~y) zvq*J8m-X>R75GU2qWN*8<7-vbMfzt$fUl(J#Aabj2BHo5FNk2(N6m#1R$~56tr3){ zjZcxwX`uL4I~=uqumxdT@%4%qz##l3g2lr-g``a3kE!$ zZ2|AfhS<(`I;}FH!ziO3QN``??F#z_fc$}HE~(~1UA>22RjuYjjb<)0mEFX7kRnZf z@f}_+|BivZV}^XbGTbsXJWoe57neJ!W*WacdDKOd{nW|vyZ!!L?CNX(nSJn~?VV<|qnSR>n*AA%8G*r=|k3~Uz*`(d5m5u9!`S~{8lcf@o+J+7# z(ZG2W+Fl`*Kz07yPL^(HD%_AqOO{GRwS#S|pb~8QiFv!g>x@57v9#D&B8+x$o+oEp zk#iQ_xO3`1pv(B|6w`iHdvqR-K=zHXH<1_m$yi)HaCDB4-JUxQJ++D6;z3jr7>k+C zYU0;EeoJ922B6?f@H?*?`Lxc@D9AGH$1XORi+GUtSt01U*voy7;w|yvOH>_AS`S=& zSc~AiI>7GrHgqrCT6D%HiwvD=75?R$CiZ7Z?-Qo$M34pTdBU3}osBb)NrZ?CM3lJ1 zD?S3OX+JxgSE+`=TdNE|3IA25DZ3kpwGCd0|B?n+2dn0m9`FEByVqh1@zX$q6>dsxyK0flwF4isQF1`;V8bjjv5U&Tzw4%*~JT4IJwE>gS^ldvHVKW-t>ipiFl4%pOV`OU*8^G zI2gk@@$ua00eslw_tlWet>XL+3%b{p!b=sD-UR?Xpsv&JYxCE(_%|wxj^w{~4zw{B zbWCIrsmT2Hwd>?SR7(?Ln@v9oXVyl&KW z=xVy%La#fg$t%VqJgG<2(Z$xwJpP>-=&lXt!}JJmyHjkuEwPb6fQDRzAuDO~-y!h4 z(HtN~zW{k}hP?_jZJS~Q`_{vcb0?;x{&n4byTzdc9@4h3Aawaro?Zwh^oDB~r`LgR zF{*E%4gg%6&r*kAY`e^B@GgVIF6Iojt$Nvc63%Hd94N3+zp^HF?|92ecu(hFur#58 zprQ4FONqiTOn?jc%FJfx!BK!jzm^iNR0WDt>!g`?gF7t~r7es&wkPG&3byM0r9PsC zwj9Z9hp(d!8eTH+vxV?^(kqQehVGU2!F-^IT?o+aI$RC`Ns(DetyZ*$xwo~+Mw=UY z*|vgeG=01-qcCw@Uz0zSyumx8T4 z!fny0cQ*oo^S4NrkH0Tpa*0xMZQ8Pt8cM3u?o0+^*6MN>uvEfPm4!}Bs zWW=v-ZY5-71l^C5W|{LDKpZ*Ss5r%Kci@$vP^J}shGr`5l+0HbwB41}6z!vrnQDYH zZFKWxY%WjgB=Hw{#qZKY+P~&xtLg!T8FS4^@^Y4ymEFbXh55~oFOBeb8w3n7_&94;(J$PoVFj(i|VDD{pQkZYni&j}fW=hcB z@J0dT$AhF}e+v(bAHd_cy_F5s%)0xB-Ws&++9>Wv$Q$j$>DJFW)A2V|;{Q>A+s6Q| zXW&$4XTWX{K%4*%K~TvJ4Alq~oK=j{3idVqx6tDpovQ&nDVU9dZ`ypuS#lEzw6nPc zDe|v${D1Yp&*r(w{-wy!UhzN6xyowMxDtR0nwAP~PNUAeQ`vNuZVFdO7w0UZ?Z`iL zDTV9&$JL=sjb`MWM?kfItDeTS(mMdZR?y2nFrcGKdZI(IeZ)|#nuQMDnVBN^4 zK3{qO6~ax4Fk_guFkIVOdSJ}iAAJ8g8Z$?c2b-IKJO9eau~VNf#Qw~`;Lps3r9(4H zqci3l!&%~e{Jd>(;w)T6{?$^XI)a|Xgj`G|OERu9iA|C&S+w?8v9Lk`Ba@P2iWGof z;fP88{yaPfBm|4WAvl3Q%1t}NlL)f+Fk<5GYVkL^0Yd?QOONqpav`%d)0V6Om6Jx7 zgmR_PeHUJ@^*5bdKs{1-SXqF-zg*5u;qM-X6#OVWgf7?%%6s@=k9*+aLd%~~WnDoQzmEu^p*FE533hB%*C+g&bxf{qD0Gj$U)ki}l=nCGunfLmAGrty7PR;2 z&Yj*`VKJ_jnORAf;<5t3?&m5I`#r7-_W4h)j>Hs)^pr}OL%}fnYLUuJN87npw4s!i z@gG+O!7i*ESApU`Tm=aBJ?Z~Y4S=l2;biUt8K9>->|2e!4H|KZjq5Z-vfaL&D;^Yp zDiTUEx2SIkQq}8hTD=WTUKcV!1$%7;D``e=L*e0KD`?Upzul{jR<}owvh$B3OF8iO zB`SO@me!fS`l$%IUFjG2b>xi+{vO?9Z;suO-s!dod@>1-)J(d(g-Vef{LkCQ-H(fW;7~Qq;b)5FhGympBe{M^N5NQce z;O*4NMHB}~i@@+Z*bvFx{9aLk)z&S+zBm2vJjadR54`qciPSyzDX7umUY7DN@$;Y6 zNyBy|D<_5A$Gnt%v0%WUvZ}+4gQ2Gtb-T?o^W-@Ej6;A zfzds|mz4Nti||DrL!yVJm+&W_cmqFPxftDQ`3HtF~Mm-~L{G1}PtS@)EWJ7dajk$ya34BC0&nd$W!xO*Aluw&MIJLrhfX z-+|TIKXd`5H_tT><2?!T=jo`@7b{=RH)SpNCF@H+d$s;J?H07$=FTvqR`V@IGvP+sB<{pPyF$>Zm`Qww4}?kRN`ndJ zH~Yy(uwnrvoQjeX?C4gJ9-I*_%*$|S>mCaV5QV+HgHp8epsLL@vagsto$R+5cT^1> zJ8@=M^s6%+C32_=_@8V**c6fAOyfrs>lsGgMiEsZWg#d=-_ocV;EVs|S+VSt` zNYr7g+Gpzki;_K5a}Spw_UXX;2fCGpkyA8dONNm>nJ=4XG{EkFa;Dv#`T`s;ReoPzy10;0@F-Xsfdzc(TeO3{y14ned9gS6=X|qYk6sR9 z+oV6%2c8=s*CRi1cIhRCN9WtnNz2}uvq6IDiDW+Y+JOp3&c#4sfHk-MkypG63Q7~e z#b0csu>E+DlL*DMran=&j;SPKo?ko=ytHUXpetY$?xmO7CNG~z1{~IDy~k>7?+6bI zv{i+0I|jnQx2HApCL1{iyjcdiDcaCXzeAR+^R(0~`;Rd>pRF<>Q+l7~XqwPTGutFT z9Ug?e-QrmBY0V)Q!PY6S`4(?*F|`z=N^f^KCH^l+{_}Ku{9Hy&lwZn!9JC763oFp? zvNcQ1EMDdne^5bfh)`^PCaH`kX5D_4#KJUk1_+i_LYls9CGl0zi&YoHqo^H52`=7B zo8#t|MzaY&=$~=qE#OMR<{pU$tGFF!(>6d#HE`O?Q#>sHF@HoK&PoUp5Av0z25$~h zqcP&0W0Ql2G#TWd)M@bZD>T#KUCw%7`C)+-4lS;Z5WA4}cFV#hdkJqf{wA{nIv<^3 z834DJe+7dt1z1fs`50+>L)nJXhvaZqW81;WqHB-#6oIp=T^XA zJTw<)d&O@~veRxJ2g$Qb&1`u|l4ocY-B(d)v)hk}r$n3$u?v>U%nMJUf*-c=wDiD? z)5lE%(_Hx{M8{2z0<&=!{GdR6HyRi5Z49}-T{YWa&1(0m-aVsmTZ5j*jJm#C#k`BO zNB$hdZ%cgS-B188?Dx2gs%w^UCkaHnKK-j`{Waw`s-V*$g2b}`(jAVE7I`Neyg~hP={6eXtgN)T0_`G9y;goz)|@-- zFKm}mw%6H@2bo7SS2f^{uSnHR(egReIek3oV_!VD>IDn>_XM7s&!Lj7y5n`ZjkhE= zcoP>hs-Sq08cp5K1#QHR8Dizz4cP{n6?!b|Wh>Vpwlzq!Pt#B|W)5c~uQJ>aZ2S`yYV{ZwVvRVVIz*<=!AnkEsa~zf+5Y%#zt7u= zy1&S0a|aHU&*!1_zrpWGT8$LW2e&Q!VzJg7C?DrQYpTrhfN6(L<@GA=N5-^g;v^tM z7@S=k+Q{R1UfEaqJ=XkFQ0^X9(s+RiQ(fN3D|@7NU-_*nPh)QZYKPpTK~HBsUFqltX`n9QtNlv%d4!t?8;)A9RXs9eh(J{^uejE14DUL z#ZV6GrL1NYe@Wh7)#PvPsaVL<&1N@GfYtSsl@qL2*U);A9jn39*o%U+QRF|lItxRa zDW2kPnR#HsUM5)#9jw?IDODh~Yh|#<8h)~UByAmQO|j;j5S}o11^5(m_x0^%XCNwj zOz&$9ZV}oPgL}JeHFUZ=dwESa;Qt53w7E?%g=-4VUdE;oE9)OrO-Ysbf7im@XQ5p+ z4TBi{zr(^6yMB&dD9h-7+rq^Tp}P#Wy{tOZ!gcZida@JK|Ios9b}LFv5_tX{$WRDn z`B_?(g{uQXt>Ae*3wPLBxZyI}xw3H2Te>RPWi8wZH=kWwIMc!nez%3|PK|WRBoK*) zNZ)}Jd9?oER3lfyXxnAf$3wA&{=szO%!*nPs1}CG)wZcDyRbPj2Nb-pm_oIWKvw<=lhi{3wFanp4_3k-31;Rb77mE*cPes#!P7JyJ28 ztr5Wy)jxl={yCWyGPy&;Ia{x%zkaRZJXY;iji`E<3WG#6aLLqJF|;ba2r_em*he%8<-#W>|5w=2p~{W{7P~XVE2fmj7_DcsA8QoKL(7ZI z+MtqBQprPbs9-mDn9DS)zMJIbjLID<5n9r$7W|*=y$gJl)z$y|OfqT;qZ1?|V$`&a zEtrS|V`U`OAmJhg3^&0V6(mv604bR$+7Lhz<>|vD_?9aAqVm4I*_Kw?Vyl%}Ky9eC ziq%%IYO%G}5w+M_uhg9HZ}0s~CVq*?Imcc@LH;}_XOH_;A$q&cK__7&YvI1%%Atr z$ilfp&kDr9HGf{B(SvEVYWeBJ2T!J-(me71tCQ&~5Tq?st({EU^GpB#e40k1=IZ~y zc|JY$qt2(_wu5_VT+OG`pa;ySH5*7jhR=U=K5h3?oc8leH=?{A5!7)L80mNqW@qHec!?7&;$SVIrOud7uxojS-&!lA|7G0y&;BPS)NgCr_@NW(*Rv+n>umpS$04cGUj*eV=`NX2n=y}c zf227teQ1Vp?tCrt>4tdf)DM|YH>6Lt^Xc~xd(EeNPo(W0WN<<%_Lq{vAyc)JvrG(N zB3(E>wPxKukjxl1y&!uc{S&n{H*hLl4d=|j>6FAT!|_+V;|T>BYp2l@EI*9M6I61h zvkzweY#cUNhfM}BS~1gzaQ>_ijH!2$Cte!>cK&Q)hV$pFbO|eE{x8j+sg{|<)qJ{E z@L!luzfCkf9H)urLFdz2u+V(E0eF!4w46V9J}uwOgjc*^CfPHeHV2jzB(w7*dFwTw zmT#~5Gzs*~r+X!TCvgv$PtPU({_|3 zT4U&)Fs$88ewt4!wB=y0`LvwvcJT5CYxy=eDnD$;_!ZK#>C9x-HIOKle`IAAY232U ze|A2d*)h(i0@a`xfNM+H$nHPfF>W&}I0w$BMSMmVnX@`}K0OO}yJLJW(@DBD<@iB6 z#`d*bd#%$=_Sm2arbqophx{gcLY>rv`XUm{o>05R^9{Bnc6yzvy*r#@qen39zL7zA z;_>)x?(N%zEYB^Dw;iIXXtH?mSpRQ&XtMe=Z^iTPbD2B&5%yfyt?8-9o~a|+aWzF{ zn*3Rf`|SY;ZN%Dz~6`K*@)GQaeU84tUQ=U>J)i-@BOEbI-lJ3e|SD= zdux`QXGGI_ytemlR=8r+@sa0~g)F@2OvnyOP75@%_5X95vjhLR%~|dbW_GFmiOt#n zd*_pdW`DNu-`bxoMbivJW{VNNBDX(V9DJnx+0qZ%pDl9xvqk^L{_MaH*qSAKkwl4%Mae4t%RA|DbqjLpN;jN zTh<)7KU--B0`%ajy{!G&$F+}{J*$+hs1Mnntvq0Vw&H{LXGiS6KU=Zi{%oZkYH8E) zfc;tRA(+|EzqCL5&Ie8>r`hq~zpy`h7`(DG$Wb3UgB)pRkRJnR25IN2>{_ZO-Fz}Q zJr#SpqOQ9HuVf##FZA?pk5%R%r8C+yoWZ0p&XX++swWu52Cg&!~I^l zV+d)M-pH$qw{2lwXb#c+NVCc$;oX54yXO;d)w#5@r1me-lG2AUduea&)Mh55oy&;U zavTfJEeyYM0W1D!kJ0J6{^Im(ycL+iq?ewiyfzzyk=nam#R&_F%6AaEc$zwo}la}F4OeQeUOt1Z* zt=nompvrFDo(0mo{n`0vOetM0BZ*9TA4I8+XAKRl(TWU`7S8)+^R3d-!XeRakbDhH>gL{HDqRou+C! z===!K&d?AB%_P+zW~A(aFyaK%=<(>6D%v8 znn}smHcK~hCayi}b2h4>R+Bpg$xJKF*u^d9jR`nHEOVOJPN2F7LFUfD zUZiA{4ij%OjuePRl=#XH(!xW1_h@_p5q!y zZM^f#3g{GY>2{Vq>zEFj`#>8^@RDP&r%1hGRB=%52?0;Ql_Z9|=kJWK+;k{=gv?Ik ztNx3xc-wXSM+#NM63$#>F?v?K^GrFif2u=vcIA+BZv&$`#j7LX{n(Op1=U{dDM7-o z_^zYZ9p5vT&#NOxpoVqXUMJnYN)`lCPB2}+aYXAGrZjIX>PUV0#87aS1fjMQFisc6pbN-bVG2{Q>AZn zk-BS4lo;XR`&9X$U;z7`rkb$dZ+C1_17hTo`SjOwA?!{Ndcjm|wOjum(zCgsdI`_F zmWwrRC%I5UwGPh+Ca1_DyJp-0G^?$3+LbHRE#IQ3ML`4sDH_Rgv5gT=ja1t}#krQ9 zVtUH4)KJ&BjRI>zkg^U-Ra}=Uy&aCpCQh;Ic9Dp|K}mRsnqdh<8oDjd{TPRh2L{6- zU|6IqR3V&qJ%e_FX%=@nh4ZdSl8g<)MvM-jucdI>pBuopI=7$Yk_Gx?`k;f4qH@X zvjPhg(UJ3d&bu1fY~dELPTaCaAUxjLtj#$FG1fLi1Lq;2t6|7ruqETh9Xc|x!AQor z{`g`3+{)yjZW&FmJ$HhOw((V8V0@c?mk}l^uMw5^XFlO}GO?@WiS+M5?0&q{Z3TNN zwA7&N3MA>$qQi|%TS~hOS9AVV2ko5Gf0rK}oEbI?tfQ?n zlDuRl?YM&SyLzi+9&F2ZYWPB@y#o{!M0DQug0QqP9SAXPA$HR^bcg0s%GR7(j&R;p zr{UxfRD2WeRTFwWSV_h4Gp6_MBN>YiV3tMjWdz_*2^(;-{G_RpVJx@Gh3S9Akgb_H z5g3nX<zbNPLj$cdd1lIVQ!4rd zeL-DG>>k8qJ>*0t=A|Dd^lDV{%y=rPxsTPFj7S#4yGHfH>CfZNNzpL|7?;Z>HCEIj zuP*<)hB~y~S@Dh{Ji3@;$R*t$#5NNFwvtlON?E9HVPJt#IxM)W;CA>Y8z(cPiGlIk!cpq4$*6Y4-y%|y z(ub4D!MwITR}VBVwu3=Zsv(m`34?m>DKP38U}iMRU5m-ox7_R)oPjIna%Nz4B70ED z08xhlsa&@^;m(;|Q3;R4mc?cWDO-lg%>03b=5qOXG^PRhiM)s>E`ENdt;@YOkt;==3wF%l*ewOqf!I!-Kv<-hqZH zI)eP@kcqlKlW&&?4-=zg{XICEuPR1>JS6JIe*GzJIa%qgLz$zU73uHCPEYA!#T?88 z&sAs5A#zL|vx*7dVQ!K53@i-$U+N!T%?wJv=)bJtH7V&8ISt~FlE!%37hx+}V_32Z zMkRYVo>Yb-Yfp=|+=rt^(xpMg5u`OZQ86Ii@pZ;%>AU#Xdwxx%xlq$cVP$2d${*;L z4xp28-2&H=gQ3t+3*GsIsVFHuI#scg7_E zCR}QQ^0g)9{m!47>Lu({=}Ri1HSlHaN$957v}Zk(e^HoA&X9*-r3^$3%;ofd$rz7& z1Jf`ESkb2&kAisnwNmtS4!Jz6L3a6*r>5N8F1$XPow{reznRFN(74)x=i#UC4!dMo>ex^IW#SHETbf?utBe zORrxctJ<&2mdAwiQcY2KA2sXYtyC0aT@?y&X%%?)1+epPF_{%;#kF zSj<}2TC<-R{j?SB=(G7%BGxmhVskMwn3o@1U4V^W<7ihMhcOBmj4aHAu$i>;5m-?U zCi5ymZE&$HgB7DMN|DI|jKN)zYl=tgI=Rx%1(+hZV7&UnX?lW6r##e4r$2h+VK7x7m0cQK+z?F43$E0dD;BhtYCKes8MK06 z_A|J6L~Ahy(?ELHcMy#SRqag9>>E6Lg9Qz#iCE*9oSI%Y#SU_OXV44M26l~YFlA0M zWP(#phO*3d!>?%B7HpP`s`e+>_@k!zlV|#)YW>Nx{84rOQ!?nQ>fa9M_xgubOW&xmdozd}~hNFW+RoHEr{k zZ#Lgs%=d%ldprO4llT4Y88f~y@>uiiAtMOQDkxGY!?><}EPo}&d?~f6xB$S7wKc^9 z^^sa*meMWPO#+V1NCu|Ik^`xA1SOiqsg&uT%Cfp>s`)^Z8XdAfNcntFY;=BgY zIXnkSU~)|kS*SF`EFJ4=dwtPlUqU5pfW*52lskj?%4 z=lmx|ot=26NEG4$kqwX?}!~%zZrSl^;)Y&hNQPMhjR0NRhS;GsEb_~rfk)C zFSg6u`SV=^QGUG7_3X|ER#SS$MJ7Z(6(B=>g{?y*c&T#JtMgd|1z~^AdmMdtMs^(& z`K#!7{aJV$3cQhjtIuMriD(J?dU(cXQMC2yvRApVShQpz*%hT0?F-X0;_Lpl&)_lKYooyhQU7!7?nh<*=7KyQo5-w8T^kE7i20w3t#~Nk zzb2+!TE3YXkF9vn+VHp8$5VPMP-%zx`-8{83=`>%^yCBeGhuZaGa*YTj9*wX129W}6A!1jzE8gLQ^_bNq za&_?$cK+QvGV+pms%28JLa<)SOJm zi2dfS)?;CEo}cb%FTAH7{gD|P|1H%NS@C|Pbzo{n)ZZ1>fAG0|kwMmEld^s zD4RZ>6+FiuzT#yJ%`g3H_`*-?r%*dlY~V9rkS))=pmb#_dRLGilyZ=THD7DO@DFsU zC}<;qRz+WhzN6V=v>qdHhFBhWciCBe7rq~7AD+YZC-c;7eHi-l{#>E|G*8d%H=YRn z(UvBf$xpf21T}vP6Ey8L4F6HnBR=}X=#o6?v+g{jOEUUKOD$O6rj$mV*thK!(DjF5 zem&(I_-~f)qvgk|S2EH+5O()!zac#sh?IY!zw_Y!AwMZtG#E9kWK_A;zeaufPsnIT zwEv3T@3V$X1rK>3@^o-PdE^QIg7V;;(p2;orv5{AptBDQKLp$NT$Fx#$mDYQ+sR`- zPt3>)>(sg_ZYS9E^#d=oa@505%{FBXwtVj8T;mE3wVf@CRfp1g*`fTj9_M@Jvz6$C z6%R&t(a5pJ{&Y|K@cY>Qf@&L~HHHzgAUR?R=jt)YCPQ)+&ZOjiC`$)nzg`?p2=zvY z=W92L;^St3QFRXrN~v zlE?6#2Jvf(3D-k^P&u$yEGUi|!}z>cgI&B&rp^wR4{ZAy-~4yE_r=}xpWql!hEeW4 zb?{#Dc#k^o?EIkTpBewT@e|`OGoni-RKIkAJTHUrvK^jmC~za+Qk?&e%D`lgXgar zUirJ0xMt5PXCm4OUE3qOc*|y6%WM9QTi$w4BQ`^izhlpfjv<-xg;K~K01jO8NeuuE z+jiybEWF(e&ir2{SqgE(z&$N5nqlAp@11<4@-F!&$CDq0zKH+J=8r%h?4!#&NBo12 z1&fc}-@bHoKm^6}a`c>Q-q4uausc@vb2zD%KU@VxUTO&l}roT+CNHO_0SUo^i5 zpVOFJl!eV(Q0GmpPfl+fy>RxTruuP%P(UnshXV0NZ>g(z+UsPXzP`~-J7tdKp z#s`UZ)rZAvoIgA1jb2nwPQ7JC{PHHwTQGXzRrQO`C?Z&W7J6C3?8~#zhWe|h$)3=* z#65UJQ!?XwNmczE(J%4Rm#y|Dy-Rs}_*~T+%DtpiJye;mpag^t6KilFS zZkazD)cv1mm^%s4s;{e>*CcV9w{XGe(MXCKz4syhQUf32-((tvSyJqkV{gQz4@0d4 zlR53FN7O^TF%SOFo83^Fjdf9vzRIq2OZLfU z+E$*C_~A2VUsDt2J+XfN!bR7dQDl?oo#B2MEx#$bsCiB@6xXTs6k&F9AyR+o;@Ndq z>=%B2^h4tleZib-_K(sFKk1~CEVV_mZIc)4E}K2Cp}wx@vW1I^PHY-lG^HN7mH-qr z&AZkp=b}rmNh0C=w!H6o-{x;Dy~lL^KF{9`{CVRfBZJ3Hnm(lH)S;&iE%&^kP1np% z&b}0wTx8+g@M}?h!_Z{?;-oj!Fn#EyO-jH%fTao`VBrR;*GbT=D+gNUp0RUABJlrToHKq6Mg!-fIo!`^IcE4V_oy9KiWx{nRfcu5v1j91O>+L}iFQ2=FalR!3qEAq?W~Y~TV#FJeRj@EUg7x}k zyGOm()q*m=+zhqWDYsV+$}i+%=zmBiu0C=z(i{47+BNH!3ui^*>Q2v_1tB@)r*iGM zu?Ig2d=}dj|Ly#b6MnPjeH^AJeD*K5S4}E^tQckea=n;0*x@>xdL;2r16L{Z*U$S) zx8!x%VG-{np!_A5t8*jXCmlW$xUq^m1u$Fw_24@WiFn62{{`}2;dwgZE&uDl*Hg$o z&?{V%%e`%$_X!tXr$?7XBVMh;HCf7^=6MYce+)Q`{8duLe->B?P7^oypMdKr%imo3 z3OMVto;LwjE4=QfFC)D#Qb6Iy3D1dm|LfwP1iob|;T?V^_(m!rhpJTg8u=G^-eTu} zq5NU%Z7#oSz$@?YytAEuC%DIs&~uJI8^Cv5=6UY|mEKPjp7M@#;kOH?lCN|0Jp&&8 zB-hV_*U%Ve0u}!);0~npQv8G;109vX8=e0d!Ye#a?*hqxJa`TL#8nQz0DRdz4wAa~ z^T2n^^*q&s!Y={$zK`qxh2IL?LZ$R|@$UjJqLH8C!fyp1_BGFY-QiDw@1}gE4u1x` zhVUmi{1xzxheo`u4&Mj91L1kd@%wQ2mXACkVkZBi!H0d_%D?C-mj8D>uinvfDtOJE zjMH5BO7M-}WV^`up9jAF+n#re!!HKkOZXqV@bl#laTmG#uLDwm%d-weK&`YLhw*TD1Xq}Dq8hu|B* zi(UE;g75wucaiCJCxbS-F)1`kr zcq5(FrSMt)!@yaP_dW*{UJ0DF5PgKs5Y9^<-umy+zFc~Xz<2-D^FECZkpK1Ijn`A( zF1;JUYrcrQy6|5GFA93}+r8j>QwMmoA*JO7syesvH2S8(qp&iJ|V zM4)r^E!2lA|FPh+)_LA<9R3;bBIJ!GWa#}YcqMq)-o`5a9n=Tusys8mm)+%g16=$% zg{SfFaPgbL^EY{(+PT870^ji?D3j`{5J!!)3307V;SO9~bTC zKL>mx{oCn|zn=%+n`iqK(bo>X<6{wtjG^}y@X9`sO#kp*@YUcUzkde45j+h49C#7R zGQ{6fcyQQd(mMpbvL5^thaUyL13av+kAv?8KhgQ03|0bdRNNrzvr_~4Tqej|AP5k2~QEqEn(*uL)oZv?M$;lH8y zS@;hXKOXT$Isf~?XMu;|w}WrY^4|fjPCDerF7RRC!(9A7C_Z?|@0Y=sfe&{6Z-Q?G z|CGbK!FOlHKa{aYK4bGr=N|{J0UzXWZ+?ApUenMyUemnKvs^LH{AVpIgjdaOFrQ{^ z;1W$#Cslb9Css|Jan7{SAYeC@S&bJx^ zo>jCAGOj*3G0RV~nenTtZ>Tp(+IZ6&SwraYJ!e5v{UQ-Gu6{xNqS+0-Gd*A-l7I)e zO(y=2P7%;(hcV|tM6?d+XMu((o(Ur(bv_i7_;Jr2Y1K7V0Dj{~@^XBLfYev8mgxMnSF zPi?*wjWv7Tg5J)(F{Nx%%BuA(ZVZO(mhZee9)@oFd`km zw@c1jP(O8E9lI7%Mn;p+K*iT_s@em>t3nTO9P{}Z>;v`k=+OsRboNq`-W(drmEKiN zjp}YL^JZTvCTFC+NlIk6*W?7xrKi%8(E+<3qJIDG>|kyp-v*pm-!yl4uYM@Yy{Av? z9lpn13C%D{bktQWxq@BROQ$-_DNX4)+m5WP97I%X{h}YI(&k9c;#2GEr7ts{Z1xz6 z>gQZJzJ9jEU|xn}^RiTiRRFB{t6Jtcee5)Is1OW?G6nlUa0%B4;cF=sBjfM(D! zFBH}uh0?TO;iCECLsQ*ClTB0O!mEWhEWBK6iwXWBEYdMG@^V){06~KdfxvE68>?Azv%E7&Jq`Uydv)-cNz5-vQ9B_$LVx|LYE3hm0!ztq!II&mcT9o5LdB$%3RaNs#oP5v)M| zke!^*BCmp^dn7U{c$wgt@K^9Gp0Gtmb1Hd=)WIo5;N*9OgZBuM-|q#P+$O5+vR>LE>#b1xUPof`t17b*XrtpbmxqM38t>h@*Iy3MxNA;(eOB zP`KMEi{K8y@mRnBs@)GrfK$iQfWqs9pF@2*{1)fG)8Ts^UIot-{z9PQ|6KT?%mv|L z&IH<*gIgW^RE2e415~_QgrCd0lW^kwNqC{>y(3snI`BGYBJv_Q2|Xlu9&<}U!p#LL zovVe{pm!YpWru&o;Xe=#&#RG%oXNCf!6}~i22lB4K;0>w2B6CElpy@OaFm6&0_Fcz z;rRbq@EGRoXIuBNK)JUH5^uGGJDmTs&i@7KNa?%`RQTm%fY9+Xpxhr3j{Dn!q|=8w z7OVowf0A(g*E;;W4&OS?hI`V%JnB~Aj|3|G>C~mjevmN{|LFm~o2v2|K;G2T9hr_8$!D0u`5}d|9xr5&kMCJ~mZq-h15~Qv#fCp-? zw+X`gL#A5)yNE0P968;V=UAZ1GhL9sE1dha!lC`~^KH22fC~4?89?Z50g4~(!g2q? zOzXbE!S@A;bK(U+^1BeI@b$t8|B!Qk*SR0^Io!$b6F`LEoa74GDVfzV$ocoO9WD!*%lBk#X(_>;m3KW>%{f3<_J z3qnJ3wvE>URJWt#kO-9X@gn?#FmuS)GlS04iRU!zT$RURk~K2O58ePZEy* z1rBG{Yw(84fTa5dQ03SsoOI{R1ya6a=HZ^lcn2uGFiMbiet{rmoF{k*dd0clEl3&f z7et3X@7!N^aK#n4Q>L{*<@dkBq3b&i|B=HVa`Vg6Pcm1y5&R>slak@Ti01z5q`Ase;76)ZteN68|MZbm6;# z#6PwLNc>wI{P+@Z;+F{$f2_kV79{>ILGs@tNc>nUkofO7xMV3f@qIz!-|FyhJGj}w z9fG9yB2apE)H2K0YM|skXE}c-AJbYLtmtTm!qd0Z11q{(OZEhzz;#>wGpU(u0xRYZj$>s$fe+sv{S(W^gsU%Y+(OY za3KAsAo=}N@L1Z7AocNk2j3PfVm`1A_;Jr$FGzlm3eJbV+khw1zX?*VZGyPJEQpRM zyxqe2g5(Q@Oz6wOX zP8Njj*w-u^BS?K-1{6Q877l;E=J4+chd=iTM-Odv{!cmoKRJBO*9k|y>m7`L!{Wy} zm;x&OF9|38+Z_HChyPiScC_$LAas7g!3~1&;WrLH>O0_PGOxW0IGlO_D&5D0pNl>g zT!h<3Am#kHgOv_WcChe!_$Sz36P(JpP;eCOP>^^xICw8m<^HK~=sy4ZK2PFMd96Z~>xtnn({T2sTJ9y$x zZ2F}@rGL7^$2fe#{kW6z5Y3CU_=h3?2hguD=UXuH$!Dc$y&Pn(E+H z4z6+V`ws3Eq&$Z`ZsD;G_9L(8m{VN42 z*9-@*6r^0&Ie3eM8y)O&@MS^D^|m18I`nx9rwLN7?+8|Mz~8|wzXzv0kEE^poR@)T zF}`;2nmyo@=lWNHl;<0Ql;?gy%JGbY?>czgYu0@hQ1bRY;gsVcLFj+R!M{4#=g-#t zEJ5f^2}0-dg3$TDdx6k*$XgblF8F!ID{ljjLLa>Ygsv+Dp{rF8y4E=ORYA$EAnEpf z7f8Adf~5O*LFnuE9uWFYbnxwcHr(vL1Ih2p?*kW8eqiKq$|d|#*1H6+VLmQch+nsb zMGlrZSS^^Oe-$KNy~D3|aJh3&30}>*m>}u>$iaO;=~tbxlU}(=kaBHuun%X*q(9CR zJO;TDL~mAcwkGFV*0F$Q{wn+njDH1N81F`bgPHFNF7dqiK;^SYIQ_&!f~50=gU@r8 zL*w7q9305m1obPQ1ZsQ}W$$14p9GZqaN+ceSC0jf-XO{<_W_hm@UT`3f4$topQ_)5 zZ>N0+h#XucK9S#g@q@H?IQS`*mv9}N&B$5G`VMC@)DM0|a1`q|Dlhrg z+^A-$UcuJA^m6Z(}kw}b43@e$VjX8($q~jjX zu&+L1mdC#7h^bcwLkjaGpvy$XM(UmB0|#p%QDm6gLP4K|tZp^R8#vd&Sq@exV7zk~ z|49)pdt6%Lt`x@E-jLe{W5yOUR>SbZ-dZJ~OTm;H0woyL!%p2@QDl&lf%cWo6(hP^ z4t2!Af8y3+p~#wM8y&>SB=HL_ZCCg^TW`cz-v&bHjFy*p7$OZ(Sp|uA-i%i&`epvh zXzf10ii+IsmU$qr$gNz@nWLLLZh6<_mLKN-Wda%2B%a{*bv5ZP!)vJ?L#KUWgm0~` zYGFQdgGs8p&G>VXtGc`DZZQDUp^DM^jN@|9hx=g_m5J?K;;!(w#XA})ux~kSxNLZQ zAlZFCL9rxz;;5xNsK{;aZZ3hpB6mea1bYL+2!^+H=pTu9q(6>>Gj4YTRI9*PC~NOt zoX55D3Lgtx7w`!6McJuO*P+hE=^?y5SDL~yka^-y^G z{7XssK*ze0@)LL^dcDG|D&7egSr%V)1PNu;1XN1ug1%f#KJ^||EXfa!NEq5hWGI&6 zQ_!apb2k;O&x*_gn57e|63G3TwzNjP+GL8HDmXMagF>Ig)ybK-(a9*kLZbQ=hx%C6 z4f;eLb2M>leP+-%WD7j`k;{{UzMzQtB^Uw2Q0iJC))Mx}{_$0>pYY+LcNf7^F)Mnm zCf1m$N)`4=732jc<(9xe6~ix$2gBRnTznC@k;+)ye>C^hNn8-+ZFk!3GLl+)7I_;f zj0M3ELaH>ng|9pA6%F$BHyP={PTN$LmO;1(O%>b_5?Y1TwLy|j zh;w=*VMF_+x3|h$1bat!GM?UH`(TkZN1!z0P58w-pQUl& zt>lSQ6GZQ&q#N<#ntIAU>LYvFV&D0YF%38!;;Vr*#`+E)Q>a*umSHPllTn)Ilc1W0 zEQc2Xr>Cp}uOY#gNP22&je##gqFinH|@QFuh=2E!+-grj@D;6`Tl!nQsXCU4) z_$==lLEEN9Ranb~7g992+bi?vgUujNL$)$2ZnDBWMC%l*64qIx{F_X%AzY>Es#+oD zORN;UtLl1#c2!+xpivkTJ*zS9KZwT2>fyrPtj#b$iK0gu96V6M-@>Qt%`(|5RgK;! zeGE~`HYm7G;?5w%YkxD|{@}3``e$&X5r0M!9wN#!%kU2VHOAXh@_$O)!oR@!8{u1H z+rPE7TZu;y9aIuMX2q5q>=jv2Z9UnEL8_`9UF7Q8FF1x<@w5s5*M45I54@Db__5XQ zt1CJX+Cr@w^a<4)c4!mZ;~l5y4Nb4 zeHCHkfcUCY3QRO*%1e%rtL6}tpAkw^!AR`RScB#9wl|pp`2|0qDYZYNPYl%(&crol z($!P~#u=-O_yx#(Pux39-0vxFn~mE*>7*ZnfukWvsSxoE00!{NZ{gj9=S7cczE*Jt zg?&Q7EI1-4jXSz-2iuZ<+b z(gP*X6$66Wqr6nZNZE59Na%C@!hVTAgQ!R8iuNPCEH;nuU-Q#T$6(k$Y6@-4Z>#B& z`^;3KvmS44#8DFYqzdlgOJz-9>HKC=8kcy>Pq*$4b(0}{N4#U2ZMOpvE<^q%)7MgF zF}0U`m_lU6p>_y=g8#RPG@2R_l6Z}B)j@7`s5Cl%tTb$gje+@8`Hi&tRP-mfDrpsl zno(I{p2^R)iLNLUN*vGZisq=b1%(kRQVjAjfA7WzYix~Ga4g-?jAPQqii1-u$>cU;Ox;zYBi2F$%+`6!@qdPRAuYlU$E~AQhyQywKG?t zZT2-?JI+j`{n(jq^yo*=hXr^xxY{`rRW8PWrJl9G1<#KBC^pD${t!d|T^_rE4ExwSYR5 z8Rfc?O-8a4ZC1eT2qeC$SwZY;Bqa)I6CBIntj>*6;;V+(Flrc7mROZ|A5T*eSbAm{ z(|JC_6_PQM8@nE6N#dL!Fovw~AB9C-(Z0AU4I^-cYU`%znJMPh!mwT4s|@4K;1g0- zDXU+=$2ELtD9RMljX|q!QzyRJNLng(b1r-Jxtg;<( z>G!fKV#MJPM5wo(;DsY;l7uyuAMbb?gzDHS&=2;m=Oe!A{1_;M5g1evZ~LJr(kV`~vuYlCmdX#b>fbi6Y3DMDXU46CvXgUa*Zpcw|K z9hUb!54GJ=Tpe$}4?dEuG$Impr?OmS1D1c2x^AS-D~PJ`s$afBgK(^I`_VFDH)4>R z@S<_V=#f_cEuHS9nf$9$<+r9PzG&v>1IR-y*-iY-^D6KeU63DdKOP#o%xcSMTBl2i z*%8(lor*ypNvBpQRVZpKk-=uyq~7vlKaRJ3w~y(oN8mdGdW~c~7fKd`<8SF51FMlC z#dyC=WiEsMc<0?vMzMuB-jerX-jl{866N<_59PN_4buOM)UsOwi1w$Z-d03AAj^#o z2uhD0PthPb(?;L>7||Yh>j@}$fv~xnElHz|EL<5+?NDqd9c7G4)`G`ZjUfudl{R*D zys$Dio19Vw%uQYXR>AfqK!d+GDDQ+x4MFU_@#=sgk0!bd6-nmG!G_0MMTyV(qdgYp|Rgx-{AWI|(5$WzDfBNNKN%7n(Be))ZxCrTzN z%FyZ!p-dpt;*#wr$yudMl@17E{mG~yccPcjO2S0OjHP5lr)Bh4A0n()ejBV7tG?Uw z`}9^&8SQi~(;cW;+|J7vgL6$BqgGtyKMV7hkyO01imWqD=FT8tm9rUi6r2fZs=eHT zkrT*NRQl6Co6(6@QnIG(TS-W{BwnH`T*gPd^N;)|s_9Rwv3pyML14^n>(Pt5@lw{N z2{LN1>q7oZxzWBzg3(ud#^)CHNj%`cMNJl|wwBJvOUy`>_i@ScNNS}B!#Yu_`ZiBC z|N1#%^_mmmRj+=mY~=Y8 zo_q|uH%&=s2t{E(zsZit59PJFjvtZ`(5^jvY! z$A4HdVb@6@M(dEFez(14SJhGGMJ#wG?sP?uCOt2R4PeF0aWC>%Zmj<~iN{btHPYk2 znek56l0}Zq@xIkTv!+c_YCUg*sBVLb2;$Q5pb~Xmht(nhLxxyRs^FN^wM>9qftQx0 z&W%|8YR5}K?aFskuyCl{`$LHWPT zEtP7Nz|;QJtq0NE)U-%ij+WnHLMaYL~> z*useabk-vCQoZY7>cjFP#VQpvX4wS$7wCg4%V38d!7;th1B^k-D zsZq&Ys$1@*&RsL1Da0=V)}&UMIoo8?eM#x2!nLh7Gal8;>FNfxR;F~d=4H}%cAMp| zmd9I_9Y&XLGKBhjwdml+7D;Tal}8ZYxg?^oMf;mHzj&KWVEeJ}>zT`Ua78ET83`GD zBW3|E#3F{scQLjpn2qrb8>4~Furw(1n?0gdGL93wd3B>SdhUu>quqI<8Ns_TM!e$( zY7kTe6>e%}PuLbZy0IbO-kr5x-db)AFw?U+xecmU@1yV%#j_KPPP(EUWTmZ!o|zuh z8Xf7;%IMt3SR@r{Aq90jQl5Pol&(2~~RX@oK@-!S#hfB7q1C}^q z1N_0PHrWZXU)o7<)uuG5exWwle{|oPqSzHqh$!?1k>ljB&2ALMHkuU_`S=erf_haC zN^Sa-QYEBBBRF17@eKty9ttE)K5Zo^xS9P6__S2xWyMd=CvtZCacgenUrbM;23A9d zh8gM8K+Jg2t=ZwfkAa)~@09-^G>ThiS3pJ%c?>40HNzyPOluY32YM^j3W#6&{d5(m z%w29`G^7?_mj-4KLXtiuWhby|?h>x)gcCeJWhY4rC*i~>yVd7*&2+_s!>G9NcxbAy z_-LpwJkrv&9Z9E0^A>9MQ$c7c27h+=mRopN`tQ6-`WE_-s9%Nbh=#WfX1uswr8rfO zmTE%aIh(aBx}yHkB(8R*v2Zsl`RT{rpsY4SN2rSYS?enDR2~VZG=rK<4J}zJSua{j z?)1{9pvtdGoKB110#u6^R5-<-abWp3*zz}Pt###*bUFkzO!)iOKWd%i6`}_P>OssX zhxPf~f}#Es=fXHqK&M@ybrL%85$U)8LUhX^8!@-=&h!=>RdZV9YBRNvs=agHRCJSc zOXfYJ^j)vpaCVIfDpX;qhCB96KOpEVf>L7B9J7Wjq9@+D`>);I(#_&WP`!4azgm+uvBw_t**&ZwW`KbCI)b4CDuN;cADRirn*OXPX}NWvRJqn#Q8FlRTh z&U%dk_M{xA%~7+GXrEQCbmJ?GSL{whdM4ilH8aBU8`H;FFVn^%@>*x=SAwCEY5T$o zkSz-WVMlk;{gRyXQ}zi*F?|cT1V$03IzrWw)Z2!pvWF4RG@zkOar{g6@Q~0i(YIvt zB%y-558gjsI+`Sv)QXCmyO$J^PN<07!s7AJtVDbkPbZ3TJ$t>a54r)2_E#FF&aG5l zRG^inONjUkF783p2V*e2ZpPeY3PdV)>qgJuDo|LE{Pa=K9dG}2+VHcAG6#`_T~mv9 z{1jIZB@yrZzJl060Qy!vWBLv`+4l>_(Igh9>*U~CPr244_7cqhYi{Au8alq;RaM-A zgO>Z(2=e1|ll{_&S0jR@$<(9>8L8oA^tByx1<Nl`2u`##D26{I1vhhY`1yA@;3eJMjIQ8~74y8JXMhz3PX!(#=6>egO5c zlGHWbiN7-@G$dZje4vH86OE~fkyPPLy=}zeRj!Pubr^b?GjZcu9{SwY43iLXMIwA}5b#zo?Hz0EVR;w}$^?l~dyyL<4Hl(amq zeN*d2J&cgEW4=D)o!WWI@Y^m#28B0-Z&SHxhO66(KK`?)k%FL*2Y60k&QbOzvyNR$ zOW>LswvIJq>wm_Zwn2@`EnlJim3LZSq4|n#YGg!E@Xh#Lzd=g1{LwPRE^;MU^+-xH zH(>49N{M4X(%;hlTZmU(i1^ks%p(&$Hm!MK&klWqBr_7*3-FvRPoA31CCzxA3HfOk zxu9klDIo^KNYO9+VtUn!=3K>UT;bPZ<&*aQWaL{Rp?el&$vd4UsM;88)^?m!jUWAD z`r;RGwmW#z>T)WPlWpL%?(`eKH`;&h7E-}kEpz!p+V6Ca=|Pp;Yy+npGfAfFFa{aj z=}Ouy9n4%Y0C6)>f2OGRH9ftCEjPPqN;)R0wphEonkNV?2i2){R2GB z{L{T@0W->jerNkfMU^y9;_2`PS(v`TKO9Fd-hqi4FE~!$1Rs$qzfGU1Xjzb#c-%ic z52S@R-+m4B^8jpryzM7BL)97f{^OP6#cDVLI1Ga{!m})PuEU;@yMfF^4wbm52$7& z-ROx@%VVo?FM`HWw~NkOi(RHd*ty>GGfT~$FH`7>+=4Po$)4+-bJ#H5cuM><+Y#8XA}aaQ?{Q%F`5f`U8z!%eJO=GVETUXh4?srj2DW5umc^OA$=v>@)B%!$WBj8AgY#lxd2as+{!zss-F*WC z|3^OX^NFQJt5Ynj1&1a$Uv(rxVSFkRJHDb2{u8aw2j&s^Q6p`h25DUt9ItEwc24)> zW?{c`6HoicWzo0L(Z}MMe|Qmzs$^O{FX-zCq-eSQLIOXwKY@ev4mIQ@XY5bfi@|Z? z!03@SJA<@}bq&QMx~fukv8#m_Mp(Y-j(3@3cj>jva`x*F5u1KCS4+^In|k*T5`$g= z(odnP$ob&EQ43}_T+>uK&#SAeUy#W$D*=vQ>h}-gPdaZ}(U?i+O&>SDXyTZO z=S{hw=$uJK)5eb}nsVL@MIU=k^_ZfAlWtr;F#hQCs;5t!^e@D(8Z&Lo=xJlBM99?X zXHPkA`m}Qf3Uhx>(T2*QTU zZ!v{fk7FNPIFw+@D;|nZ+35|0e_z5a{DtX-cnGuI{}VQA&88`di@y>6vvq8~L!6T^ zrd~o^!-$v*qwvLit308<>QP-)h-*JkdNssH@-6)r;%D()l!cGxyEqFU&$mP-49{og zcQ6~f=Q-bVNklgNR7dL(!aq?d!sldSTe`2@4^QrgF9ok5t+Qdg;`{sgd*Pw-Io`aX z!@R}?$zd4I29ymQE--xPsepxb7~^g8sa)MBNI5v@1nd5FpwihWoOJFNB%NP4 z_g_2rKREZsPulP+fC_)3AmP95-0yepk2v>P@HavQU*+I+4&LhEw;bH);5G+;i~t9el&VcOBGSN98ln!7+lAYdTPL&Ju*qX1Not&B0X;zU1KF9X#?=Hr(+Jj&g9i zgO@tE(7{dz|JT909Ng~UpB;>T+NRsb!6O|!*1-}7M>tsN;1~xlaqw~nKkwjT2U{KN zbnvSVe#^n{JE+%*#D_;5+~wf&4!-E%yAI~iP!&GrV1EaXad3u%7dg1t!Bz)dQ>qIu zXk_kZoc00tGs+Uf%GJ4lg!>s!I{ja6+V2P5&v*r2=4nY9I}bK7JJXUC)8c1v=gSKQ zn-dC)TgRJ~eM6 zN)YDf8vz`Z*=(lu91-^)H|z5`aGY}ZA)#wd)q zu+x0>Vn|S8c)h;IXKl~tYWLaNYMH;vtjv;0Bbh*;xJ&V839PdlBX+;Nt7^Ha^6>bx ztE;Z68(1FT4h^>`h=XL@IA>0z5g zFxb>o;^nY@w50SAMDW7mtm`s1ub}*}_BXjMv(9Y3aOsEX+;W0JijmZcqq#1Vkb@Nq zo{3*&8D7zkn=b`XiUT5=l60hLwLNh_;)Wf;@`YItwPEi6&< zL=DMTgAIn-ihedr2ZR-E8xEOhc}!B4oypSkZGEebbajTU?8Vx3Qd@(zYMd#?V1OSx z%-6zEPGl>z8-J@bf*~Q7V3D@&#TklRpt#4E*o_eQxn0h7qif_KP78k`yhHQyLFkHi z-bL`9J2aw?$YNfvJ2VZVEb9)9k=yJ$G%XNoB=oFMLfsu26)n6&QwzCuO3B=zQE;iJ z@D7b|bB9L3q(>@)p{OpHscT*C4o!B`va5~65~njN;6UcbJM|*7D!|EKK}1&zo+As# zbe`8v)pC($CyTf(p_bI87EznxWJB1lP=>6SA-IrOj$e;v^b0$<)WRB;))^GQE@S%~ zUPQudJJ-ggSW9bO2GzM0N2r}!h00={+PUMRF7eoQ-Wg^soqm!U2@%4q-Bx_`o8}Ua z@>KFc3wyTqFaUDel3Q`RJ7h(^FOV<%C?eD*lLHwo!!3y3Pq}yVr4tBi%wnfb7O3KN z>!l4iovLjC@|2^!1*szjl{nN8P!g|zGhM(M1!MzKx?LNPf>Tm<63!>EMwdC$crFO&UWb;3DfWb++3^)nO0?w!OD;P%&#gO^X>zMgO}qyleF2$bJ|Ajm1+ez!twrA*2Oc2p6< z*Et_s9>N)qq2jYqjQ+OPo3jdnG@A;uH~L6G$r5=4=^z3o@;W0yUD5C2rD7xvbk|@w zuu4!Bbc>w%byqV+TVt#GB#4$+B~FRAZ7L*5V(Tp170isN(=7xy_hs~0FR)B7ZMcNg#0>^70`ZRLSo}nMwt(mi?Rzv~sK{3$x@Y4C zj_dIzZB?edYNML5S8aC4%bkWjjFgP%Z89CMy=|kmVQ<@Pw?WNt;pq6Pvzb~Fa|^Ea zwvC#Jy=`N}*xk0-jeorDV+3}$ZT?)qr)yj5Y;<$sMs3JmxT(~ayKrNp-=#PO=EBVy z8{N?9w(iWGn=Rx+8H}7{$fk+YPjl^tsR{f}5-_qSK~J;J+zgDj{g{O;q;0bj zvO8}>o~4eI@Q`&zvmz$!EE=Y|3kn=~v}3+hvZR}eUq;~E*wK`46JP$LcE+*JxU0+I za<@Im0$8aKcBuD^K6l1Dr4%ScofuHD+}x3X0@DcXV3HH}H*Wsp#yKv|uNeKpInK?7g?{N_ByR*|m1zJRq76zp)cIL2^*MK) z#vaM?pI-WDJIkOjs;pG?PeR2ihJD6dF#4VUbnEZJL5e1eRmJ7ubTQsB!8YrAM44^C z@IXSNVZ1vzyvhorB|Pz0zwi{wVpL4*q@`mCFAk&%Zx2fRG#nTIHOSIzeT@vs=lovwd{M59nMtkPQVd;T&&&u&R$;3mY<&cd=uX>i5R_31`n*=-U5HtaQ;Ai= zuu=@m@m*_Ghw@AnoPv!3 zJ0NqFO+nWYF1K(fBB1&V(1N?R}G` zg_|^1Ol-$}vu@J7muE^clO#-6rb!vC1nL#Yf50#QvHF5dc9^l*@C3SyXH>Q?3|-~N zbVXTnCn+n(gfLp!_Hd~}-3d{^AeNuoSL;iD-+0@_WX@gv2EfWS(b8#dwyNfoAIYdIe=1VTh!5d9XR z)tC9$pJYiT_ARd0tg(xOrPoD+ciqH=XOm?>pfwat&XRstB5A-%ACFM&$fRh z^1fTNud$8Vl}2-wdro%*!qmCakbf=yNYv0nMsdffw^^K>d+2#_q%nYVu!bGOnb0u zJp0y73%72xa-!t4Hs$i-MoUkBBmHc~hWp>Q86UOxZRE+~l^W3g_iao+rJaTFz727z zi^qreZKQVtbKl0$YP(o><;Eh$v{TE{iLRxE^l_#I8tr`apQjIoi@iG2ZQ76S+tkE6 zSBe^Y%$*h|QMC7M40FtVn_2X-)d#(ABZ1Irmpk)J$_>QVeVaC*R=-++x>qBa=~?u$ z2Q}qh>)dCW@NH)9uKPA>S-Ni{m|6TH{b}Gmi(ghH>CClBKkL4YTAuFP+ycZ~gogKR zDo6tLH&FL&oN0(PX0YZi(3CNTbQfs!QXtxBy%MRy_<&geRVQR`-Bj}BB0Zx-?X8=w z`gA>4HP;y2#hY0SJjHh|-c8yzpN38CctfWe!zti^`EcB z+d3d1Y};;@K#%2S2@g5NMfpvZu6tc)H;u{z1~k^k|4Xa(7>oiPHWsB)EUpcs@RA6> z;77X0$>PSgrMtqhzDsM3>EpYiU(}>5JzPinH{0GkstX~FL@(j057J)4XR2yN9@eMq zDk%##7>@9VncG2Ekuyaw8G$+ni3t=)R2xD(PcE+_JX5H$mDp7?Y;TExay$lf9kOLe5VTFhUqYXq|rtX!>Dp z*zC7HfW9w?B0vS)(y_B^4Z*vkk@N)wCTYWrzxL;JjSKFE#+!QLB$chCcMp6WYr)K*3>rH*2(J9DkItcv~P+iMQ3qSEO%0& zl>G9WS*lK^ui)lSz?74cDMx==%G>k!>Y(MzQ9t27mHr7=e02Yto0DB*JOW6n!~*}& zAbJOiY9&q>QSc-F@6wmp3qXc)YeYnOlkY)EA44Gx>6i{#XGyQxH{9bfwA(WgenH2c#|fj>Yc3$o!5{t^%`#qLSD8t;&jqB9SudkhUV9lY zMg~OF1tis+8i*Q34az|i0&@XL#g^o&Md$*OT0*8}kbokpLD-gK6=`^HM;DNkL0~Q* zRg+`-Mb7Vs^&M}owYPOz6egD$$`%rjcZ|gqWTTMIgo4*y^A>753>ZZegFUd$()p%-_bv-c`NUTPHdZttPjE?ga)URyQLVB6qz6hO=< zDZK$o;&<)I-C#KEzqa+Y6C!_mT=$X0@t+XJLnVlE$9cKjqkr*E5xbwhCkGWTD7^0f zV((qxqpHsJ;hAIyQXH62gMtk@wxcCx&;){JNU#ACj2a;%;ZhqlO3+XvL>Ov3CrpA# zls@Ay8$Nm_i9%AfjN3i9Uxr`kWcPbmaVNds!M(}P_?vK%LbjK+M4qk>ke7o-hHSA1e_XQxXEO^VcjI;uyAX6T+o|9`0ly%na2iqy`i61VX>k3L5NB3lC^ zBy1~f8fjChM2fY*sa;~pe(~uTFI%u@(F`hZ4@@|KU(HYPoD-mlP{x;*9YIUbjmH_`6@mL@Y7?_vA$D{i@lGrOaS$ zuwHj**C4MxM6P+!xJH8#S_>C*8{6rwHCV6bNmn9^bm!i3%u2k8=@{(mP$ui?RNt{P zOYTlg#O*3LzgL?U!Izo+X%A7Vb;ZUph+Rc;XVyV)V`Bm5(VNJR}Mxeh)j8!DzU%GN&Ti z5LMWXM20v*n3*_n0SBz1`1t0@mk0emRT^%{NMW@pKyQV#QPurf4s7x-j64ls8f-^QvCir4u9m! z5*&PI-g@AOu{N>s88t$DyG@jLw zpN8ew)@bG?@AC6Dr7a)Qu_N;d1amX>>x|D~ze}4N8yp zd$>21mvBP*EF6$QUflhI!{6|D&RK>E`sen{1^;i|rNh%D$&YP|-{5|^79CC%%-P?t z>e>H*>^JR%4w`86WrTcJa3|J8nZ95QiU($_%xQjC<+jfa~5FZyNHC%*;w zv0qLt8`1*0wB$$q+4wc%#~o+7_vlVWb+St7xn7=NUlwUtvOMBxSt2*Yu!x5r_Ft2L z>?bc3{Y)YXuvW}}CFVOtpAbC{W6<6EV!rtLYZpY8Okw$@-R)jAvNqtv|>x3X6u{3geEsqdLr4t}ts9CP`Axz|zMlfUa_oNS`RpmaEjNUEJ2 zFAh~Ps@}4ps-aECStWH3Jo+C_A409_Xesn!l^bA;19AJiKL$OhwMOxLUvEYZZ0VwH ze(X(soxB%pUw-=DJ2T#E^eBTVbc{l1aN7SPIv?DOW~lZc!qBy zHPHv0z75PaOQCpb0PE5K)}%f6(Fn^+%ec+DISX;rh70fT_t-Fw9a0v)ZzB&8yRgq3 zUIxrDty+LWL;S*GW2AFt+ZWYB%-3P6yZNjitI#re7DRcqRI*Lqqn0Y3=_-9! z2e5+@&;{0Zx*KCO3z61_OIG1r7HSXW7{Q_1RwVtFfH?_MIV_)kkJ3U>AtT5Ws&1t@ zN+q!5o3Q4Zu+}OpHYc&sA=n1XH(5j|@YqaF5%?x!^BGVlr>)j-s%?WA_t+GZUu;eZ zK#gS=3l+j>%uy9oKwJCsjhb;sO}dS&?rU=A?17=2@JQpF#@AaB4R&R2GD3 zSUL)8EJK+Na#nSvbdaNB4VSTuQ@(1?Nqp}z>9aZIt0>1keg z+U0z1BSVQkWsM2|ao%{8Dy6RdT$Qu1hiAdunv~7Is5*!d(NYhF(|y}Tpo+0np(N@c z`5#5!Wc#+`I0f$B@$jbcidp-LVgIW)e8d^4%Q(6Z6|4e5!m5fjN%*_ZMvSm%LbII` zVu)7-Or3AlV8b!hI&q9{7up?s)>|dF!*v7=lr@Mg()IA=pe&rvIi!KA*sJk7voQKN z(^_J?bra7pr;uv+oCs;*I+TT0lj@m2+t=rK;ZZqYr;y?Ay3L0OSr(`hJM_3y?uk#y zgnv!v4)y_1^za;UjE_=1c21^8Ie;`?`9KUj6r_)S+Qu1H5l-TCjX^J;($XML*VM%h zx!gFzX7113V=Cbwx~Z9?Dj7SssvtSm9L~}jyqBrSRh_*m@~^%XqprVm6Uz-dak^nz zp+}G>NDtX$jb#AdcZ%!oJcia8^mqM+!Pf;FZQ~7$t2cxF6JQ;u^6f~&RXc`aWa+S2eKY)wUR;9_UtDq<5zn$OT<(?PJ&12 zAuX$Gw;mMO%SOvIeWM1^tKLl`AzM{W)9t7i2UZjzM_dmNv9Ro2ZRq*deAk7^73jOxEC~9jGbB~;qA7RrX(z*g@Ta#C_X9 zAS^yturM|pYd2DFjr2Z^=rggO zIU1pJyRohqyOB-7d@X*{p6=ZkphGyaDDos9n)K6f-?LE5XX(vgIQ;xQ`|;PB6yRT; zY0G}l992S%s}yzxw$j^0#eI`8I(<`ml4+2`vD$vv9xyK9D) znG-%BB&AXf8qV=|PX-l8FQXcW8h2PWx?cw&JCbL^(6gb8gF^X^@s@>S*=50TeY=n=Rl#=l+i_nkex7rN>P2f+ADiV~)!Z&qDlF*75-O00Z-ykS1B| z2P0JxD|Cm2F1T*HQ3{_;;kQlSTV~x`hLSZDeZFHyiRO}z@K%CcR0$yMqbs^TP_;PF zYCypufA=4lX;t?KywT3tqni@S(o{=>iU=7FnBz-PI#xbXP;XA+V8{bLD>w{5q|t9oE%^v~ zc9_`@i*TS&H}+Fk!?77U%NolNP7vAS?>UQ80o7^PvySUNjdQCylq2U7>;a&uwQvGo z&kM}Z#nvbWgn8;(f^Q98Rk}=1**0Xtghz=&yXMFcmi;JdpvA6ysed*Ciqs%4t#js5 zaN;_+t!^BLzm28%lbp5c)D(UUGv)^4O@6vQh~o^2mwPbSI73hhCm-8Ba>unt(0$6d z#xV=?h{0ppF$3YFBeDx)2v`kg&Y71Ks{vONy}$ca*3$TFrbHF6c_uyUYR-7U$| z%K3?@hL2AefBdTxYV5g<(G83}7*06$gjRXqx9WayEUbc9z66B_^F}M@VU!R@bB>jv zGqgZ6yCgAB)i179s6su0LIt^3t3t&BViP>n%tKAFZ09zTN(RdIxSA&&SMzSH4iaDC zAaS)967wkkaOl~47% z(?L?2?RzPHO5BSvepDf}&X|;(oc}APUNIN!>6tiNpj&F3drVDJot)<|s!j{P6Fnr7 zv4%4Ql5XKsbCI&vYH(IjtdTk9Sf&NOu=did?|JC-R>6!%c1~8%Xc-UCi|R}5oK3pF z%{vv|I$^$n`PCh+UAPi5v-FiQJA0Uwy#^H%9u=a4w{UZApmEOg>dAsNq++8Qxzbfn zwSi?D-aasPVYtqbi$#+HumidLPsT4yo6SBu`^nsXkOXGWkEf1aXvt>fFOEsiIHdy7 zd7sKtW0VY@ss!R`rn0kf6kU-_?nllUrXB!M(CNN!>#mXK0QB@?ugq>RrI5Gc^kM<) zm^@6@^oXU5AlcHM`&+si^L&@D9XfB?95aRB)*AJMK1m73yzkW?AgX^RgFdPH5-LR8lK%qT10MHK9s9` zAF!q|K*PXBojMuGHPxk!s5WQiJ+D-c47ZqNwGfXFsHGMmILuK#j|ya z*9Y67;SP&R@qedz`>P-ol__SY$rSVHM5cI-P>V2XM+IQU6h8}AIiHA8x5{LdUk6de zCD!p)zold(VhS2ayv{>qiWCw@L4nB6cWHvn5o>-Rj2Y5E?fZMi!YcOW2F3w`!>aB! zbILeq?Cf9TFPAyBxPFY4qJ<-o#WS*^6Oe`m^KnJwwsCrKep?`hQ?ev=xuZG{Ke~6_@s+q*TF6H`e);$@e0N_w z0Cz!J$QJ<8zEse4R|a=#dk^OP=!U;pf^HV8;Lgn>tW=s9cb&MS8NYhCOZ^xYzb5=# zHT87ohE2U|H&|xfQn*`A2lBb@h?rF*zqhf6SqcLmOu$xC<;V1*=#ym!r6(Wtv6Tw> z-0)nzi>c=S$UZyM!H;D`nR84F)vSN&kqnhqS5Nw)8&^-JRd$O00;uW7wVwzzTfM8l z2%Ri({1p8aP#31?YoIPl(UT`#lA^x`>e3YbBB;w! z^vzH+4mZAApsq~ON1?7t(LMc5d zlIN=_^7NKaoF0Yg-F$vQfoI8*^9v?;Zb3IT(X*)G`~oG14v1IA>!p8;&>3+ZU-;v2y4R=g}PD(5=ni+Ce2 z4Me#@^xXKO`Hux(5&TeaBpM9uxxyrl7ra>TYQY-?dFqJnHVaZL4fSsczAyM^L2hf( zzC>`2;3C1V33ds7UGP4^&4P~!J}3A)LCRWW_rI=O_%YE5}Y7dB{)~`TEQCxZxQSe zTr2o(!T%8ak>Jk-e=SJv8{>USFednxU^WIp+Fu|zRq!&wD+N0Q*9fi`{J!AN1b-{I zQ}9*6qk?{PQH*b_;1>k*1PcT&66A&j-Ioi_6ueUKI>AQ47Qv|CYQcL1|4r~e1vd*m zBIv`w$@s}7lKa+9u)j9!FL6Dxt!tW2%Zg0`#gB{ zqF*GqT<~_mdx>ag_ly1~f_$lx;cXM#EBLgaBlxc1Fia%qJ|Ord!DWIif-8VbSBL0L z!S#Zh1b-#?Tfx18&k4o^UlB|Q9u+(;m@!kPs31;c`u3eFO|TJU(Y(5y~)1jB;U1TPbuEjU;3YQd#~ZGv5b8wB?WzAX5v zU_$UM!S@9}798T2^a+j?JXi31!HWei7o08FAox|mC4wsiEy1;d_X++;@I}Fw1rGvQ zjtSAfCCE$EEJw28h^GpEL9kG;N^q{=)q)Lz%LH!~TqSsy;Jt$P3qBN&2PnlHmlu0GGmMg1!GdQW|m)xKy1Fu=JUxF~k zbPP8PHc$x<`M5h`RXTNiRv}JmtuhZmEtP{4q{mGd3gr}QRQ3N6X7`sCD`y^H;swf|8%4Z z?y=j)(4zM^eFZNgqXBT;do#)yEI!Ri(keRR=eM80-|5;Pd?14F$+oRepSZv^2i(Dc z6XZa$BZY>hUQs!zQ(z{aq@M*7$;V7eFt3Qt&Cm^Ra6Q#8|uVF?W?`%=u5b+ zq4;cJ#i#RkEs;bN~4p_AZjM$qH z_&1!Z*^QX(U~?X0TJnU%1XSW6-VQIFwj11_v*D10Ue6bRBd8I@N3e5F!^?-7d&UiT z-zrlvUq~vJaawrW#wvJQaSrq$ya8pXEq!Q^tlP~~8Nuek3WD?dDmAvlV0oP5=jI;u*}L!&xRuoyovM zsp?!%+k^qR3HmS&Y0vnXV;r$-cY5OLJjRT8TKGw9-zx{vm-N92b1WmWQ~~mhONSfH z`bgBI0AqMZpU`NV7<*Hn%~9MgBsPS1Ol+KOP^V>hOa`ZAaGVV1WR#2Oi#QH5i39>t z86*9HVtyi%^NS1D`8$7_hTLE&!M`d`pxC}`vE6Zt3&hx~vE4ea&h&v3FfNa9G5wAm z@EhAY=-A7BsCt|VQ*G+NJ8a2L4iYpPUcv|bT@!H7Zi7nQ*648daxu+8jrs?gaAG(d zS^6weWia1fiaX*yU3{qUD%*GwPt~ydEi`ov8{f9;di!g1?+eOmshKyoF&{CijqTJ< z*lA}Lb=Yy=i?LUo(t$jh&$+qmW7()&G6U8mQVKdG+jt)ekAo){<6dWE>{YOiGE>g( zK%y~wuEIVtN0rMnr|FWwD>EuT{_Y@}Wg-iIH18g%&BB{Ek(x$!G|WM3b)%4NlV<-m zmcj-WRn_ik4;*9iJ~@{MIcCp801X^_>fCL2x^}nS%Yvo7YP8WgPAo>e*vS5(0!aXv zq3U>uUATR&N(5Iwnt9h)K@~ya>PEm2_LD-_pOe1F2#*7Ur zt(w)PdLXlQpJA5m^CWuUN3~u0({-8n66oqkOb+lN&FFgA3T@vIYm9C^FvKZA9OF|} zz+o}_EScl+YHn&qHg+Wtk6|OT2EYR7cZ>N%*wvgGukrJDTe#wty8U>~(37TfrFm7)rlmJ`1OH_8o9G574c z2anY>!Y%kP5CJ3;6No%jB+^(T;jIm}!-;MD?C_6)Dc?WFi}>HcgLs!zBwv;wmYr(f z+coC{DG!4Bu%uKiiiAjS=ZId-7ojf18a(x*JAQfi(Y@=AYyVnW$mb@3M1?Li$%80` zyP)d`7{HJArGgWH{2Jg6+ak%2Zupxeh$*)En&Hlkiw0ElSBD?nyI%|3rGBnm6AWE7 z?di@9n|jv{OM_%yX?`c%EvG_0*BudEa`MacVGkV!faKmh>x9X1%Z`qVur}`1kS@(@siJtc*!TpdAN}t$bBH+VS;Drb>u$4 zr{X&lYQ6&=0^%z{;6Ern1{e?nEQi0BX|TG$ME{wKRwOYXnycy1b0_qW_WL&jk+%9v18u z{IlR^(D|rz2wo^yEI3v062Vr%I|SDXeqZpXf?EY27kpCi1;GP?|1J2Qpv%h`fxI$Z ze2SC!1;Jdw0>Np5a|IU&-Y9sp;4Ok(f-W!QF42EqaEIWNf_;Jq1m6)nBIp<1#o2=6 z1t$tl5v&rtMzBfnUj;h^zajX2!G{E0-pPxie;Jq-@Oa)7{ZQdmoGLh0uvl<55p;W{ z=&uu8Cb&{?wcvLI9|Lj^f4Arl3jRs(W5FT9yEsK~lweS>0?2S?ihiNs62awyw+U_# z{7=D$1b;2~m|#rs6~QBdY3OH3H-mX86UBU*;AMhW2{s9SP4F9n-xnlLgnOi0ME|(p z?*x}DZCDU#a(DVt?#)g*`Mt7&f{QMi@G1BDHgV9!$8qtK_WD-7z8-csvh*NfWf0B0 zqn~o6|=%#p6Ou8H4f~POH08)=!Q&I)Z^h!(%-k|6Sp7$bB z!X1%Ey@=HagGjk&L>`qR@<0{wZ@Y8Db;EQ0eNwpMZXUA92q;8MNAyV^J}Cm%{~&*Q zdGdNYGQx3J9n{2a8*6ZQ+_5Clu=838E6Y14D|@;So9dEO@#2{D-Oc_ne1` zHwx%!TFNUP2OugI5-5{C?=Hpni*I8rA zA?t;gGH-DMFEx{*XWyjxzBC&TO4P`8 z3DD0$dTw2FO!9f$c+?7~Uu-@%EBujN?TzvYaSE~5rCuK1$E+bQU2w1Bz1%?1eF((7 z%s|HIj%f$gd+>U8$A{i%`6Dbkz1Or_Jw0wUeZ3!H(pP%Z-ThLW=}mX_n@x99pb104 z(Y*@uCA=v86w|R2n}XPlR+7uRpNBO>BEcXVQgxXOD6>#3EDv1@C>93KXWR>idS65l zW6I}AFZAMkCq?S0wENO=&=)VGLliA)#=rVwAAD$;ji{=uj@Qy`pLY^L-nP8pgGVs{`~|%#Ld+hD6tGS#-_Z17=CDhn z-WfuqsH{K08|Xlbx;mrRz_{e?lZFu30r?AT$%T7xsL$4<$NhkVx~%VjaJWnRXc z*}xeC*;Lt5_hsAaxnYB}kP7XRpCR0QkPi;4-?qkOC+OFJESv^Kr2g&&U{_0~`1k=& zW<=S76x{gV40HQih`|jJxbUeTEd-Gcsd?S8*MjxkvJB$SvXRXWxj2lg2UXn#`yvs zzuu+VBH|k;kH4&Lf6qeJCd4+PkpzIXXhW=xO6YTtAXRH8-mB65tE%k6bS1@{8PZMK z%3-odE0)h|8)L$cnSVw(7n%Fb*ovENE#D0#!_4EpS!*x|F>lKG7S%qHW*@rbke&Td zvOfpO9b|w;4^)b{j61rvMuyEW(~!s@`f9XaA2z^SgQ4l^LlI@Hb+5S}+91Slj;3u9 zNM*D{Yx+i;Z|ClkWSYhpdjRTBuKH2iiZW-Bb0WY?CFFNjQX%Ifn~gP}d?W^V!cJqZFg{AhU5B_cN4q4#VGd2j*Q!UlnEa@|+S9 zLPs6H;tT{YV{o4NSLPTL?zIK(<>7mg>CFpFw_@KD*~T^J+9;jCtyoQK zj^#S$)8*3tfK%4=tz)Ecjx+mllTExv&wg0Nz7q~vrQ!Ga?jjT(+$qFe6;u#zfR00* zR+xP&3Qf8@2wOZ|BjRdv?l9|qtOQk0EykWY`l1SR*NP#agv!HDv#!wft1d8NvyGE@ z(+gLjbV<_~Izb?{sw?fCW=O%POhqry4TsL$@eU(?NqYL}<~$vrxr?zej_|J5XTaW- zOsPva=HBQvw>W#-1D2k}0`%h?a8XAsO*`xvONqEv?f0;n*z!`p7yt5~%FN~>-l z;W?`;%6QL4Ld~4JkqMR=S`=mI9-^|>m{S(S$!3=_Xs?aFOGdUBo~$>gkj3gY3;_i809VK&kR{)c`Rq#D_N9YM~K49=h`h!?q@V~QFM-v=Ei2dd{dhL4M=R^~3TteA0iTjZNl*+f3-*+tJ|9SV#H{EV zm-k!cRv*fRqlV72KfF&>XIqggQxyJmuXY!Dg;NpwAK=)`z8%S;H*1((?hWrUcS5et z^Q==;abYROsC-?){+@rQC}I81l3m&5vBpRkxSwy8e9sJXDof|vqkmBT-Eb34^ayh8 z_%o$VC@NKHi-xr%J1uF>D$htS4Oy$#1za8iN{%(V;e z=aP!*IlQGq1=m{2(zW8`Ouce@vSBp?VwoeMf(m?TSL zG7fvQYV?$3%UshZ?YUl5?zw)WLet&K9c$ny(GG?eyR5{k;GA&;3BXj}1^x=$Z-Gv` zN6w4j8Dm865R72Q6ZN=D0}tlj#vC|GUD3{mTYA*5Dxx|`_UaWwup_&km97^>$cD^k zZUG*1XZVF=*UOf=UbWO3bPElD{&caqajJEb)J$qMoH!mC}JkFtq`HBo~&dI?>Vx-*ex~c!bdqHRm$gx zL=5u8EBrmb1YoA(qqGYje5>|<7DTZljqdyz6Ouw}Si*u+6nq_R5~o5#na`L%C&CmO zu4VD|dQ?5GqnK=372~2(svIrK(OLO=T!+o3VNJjkNIh^!`eGBsn7t0bSY-Hy%46yl z>+jykH~i#%<<20N^dOuzs~FiG2S4!gFwE$CR_hIxrK0j78eNt;JsNy$z!2=XD^q%v7Z4=D{_d}# z{IMvhNBY{~krVuz`AR9FAxd+Qgv+Ge$4%`O56r3R>=Oso&&r4o}(-l@A5pYDD`)~m8Ei? zPtQZc+x$HTV1P8JjCVf+jq|dUgUNTVeRSwsh3onwQJC41E&u8Ul)lsF^q~=ljOkp5 zgx|CLD=4Qr+s)GI(aI5sfuZYHopgA7HHtLUwc9G8AmO!2XO`T_2bQKViJMi-rtddW z_*$~GqAgwFcFC|KFQQHr@ttK}q+T!@Vs1aOA5>B2)iZGQPUl+IgMOCPJPkGWAoTqF zUBBdV`vEnXv+yDkX2_At@uwN7I|c_BOd>YK+{e;~T^ioo_Af|OKaFvh6ZKllcTw=R zTDix3oTtxpJ3vHiTDDQZIUVM^kgcHn89_oClHs#n1eKNK*fYOzF7Ah{KqN?zYEb+x)rmF7>$dzemOg{MY*#sn#Nw@-RSR; zoE`AUZc`;Eg4Dl_&aBnnb2`>Gh?V8U_jOQCIdGC=6`B2d(@Q0My&`I}kV1x4otAh} z^WEJHP^vVN;W=^u*mMBzP;0&aj)#IvzfZrAJHKmyvG9Xue2c;*oP9 z+}BKS)}eAm}OWejPQOq{Ze){d!rAbV)))g zGsry02s4M><3ZFY`3Tn2m`Aj%cvTM&60dWLxm-hf zC~UrV8LGdb;0-)cuLlVP7C^c7AshV6kC3a?I@Ii6!7?j#Jj0V;n{}RyZpfh2d5D|| z%E|KXG)HtiZsh5i(zrGUUy(Rs2@YaW;kw}=nV#tBNJu~>!@H9y2uKQG+E3G|e0*sX)CmRd)7D zYXX)s4QAo5FxOSP?xeFk6tOvscbkVG9@V6E37era?m412zosD!cFS12vyklUHP$fp z%|FIA1d_yF%Fgb_>)~1mw;AGo2~&jztcObkO`kBPV>A0Mr zo$!EeygEl=JvT6o`&SG_-@$nT+!4@)DcaYw2@G@8q0#Ebs2lA?f2Gmt#%&dxtkFV7 z1v`)M3n0hVwu=#CKLW>s7L`TmOXI9F%s#z|t7oa2y@# zj^z@e9zV^{w?H=8<{S??+UY2aY?VJYc*v?(&3!(b`&wOPTY~o@Eb{=;2@wDsM?e)! zcpkfK>1#`HMA@#yt3L(HbC6Wk{B>iMmxg3kgh1J+LpneJiRQkEc^1N;S+16dV2$z0 z%hqmP%47%6t6~C<-hyQZkDlZtjf=&iFLiPJi~O%^Z00uPNt1y-nvWrfFm!XTp64eQ?IBiAM+n(7uz## zZo5xM-TY-Kv`v=O$}rYaj-nPSQ!NyasYxp`N3(SlpDttwS{7mcTD*#xzH&z#aVoCe zk(UoYgkYU9(#9GUyyjIWU3e&KE-KqK+=@LuWyQ*5y1cLC^Go%u{NtkXGAP8z9X~k~J$B5fj zfQ0tbgyqO?TXj=Ohd{V{jHOOpEX#`4fC%Qo8&ZP=$(KYFKyDR>{}Vf9N{#ckw8HqKqQ3^e7iD zNnieR#Hc8K99~ZHz8QW`^{0rRd)R>$mm@A_5eHk5Sv7gk@r28M;fW0Apjhy1`g&bX zO_<(b61a0Z1eq}7n3P~YymiZE{;o^edFXeWq)8m%rmKos=8K`zY;TcQMhJ#xRxJW;RDtSU6a?Jp?}@TK$_SymEsPJG zePWA9ZEm+>1G6bug&vS;1}9j-7L{Dk3{wram2g{z?xYkHSc32r{TV+)3fVO9*82?5 zv~JFD)#C4dhsMIF&PDk!*WnBN-FMI&aU(tz^cm=MDy?yOO~EGg+vBj$j0D4pCf_{l z)4+9wxW=rs46CLI=2=O1dXGSf#e~CiioTyN*ZCltkNwkC?lxi$Q+H zAOv>an0_tyOeF{O9o*!C__Rw^uNU6;TO^fT!SjH&#)0z!h(TrF_vn$>C0KiwahW5# z?zlWP!7Titc^;xuG*CFqe7n5kP+H4rw(o~__M`UI$E`HeiwP!nfiGYFp51i*al7^6 z}eq(3T+;$v@S zmYmmXs53$cuL<;#kI4>Nz#AMgWC%>Rn~&#_)77cAtl+bgk&5_aEcrl;oUHimMc8da zC9Z}haTV1cAcO3IEMFFzIg-OBj>SG6LyQ>U+2C>P2)EZ&e_r`(PvRVQl)^_3@u@D| z*ng1lX$wUSxMd&@+mWu3AXY!7n9S>RtMCHL$W7ER2X0^Slf-ZEgdFaBOyo;)x`}c& z6oh0V?4UPJf=73U6S3=ghFU-Jo}K3C*x44!s2+!B-jUYVb~=Z#)Vdk!@B9~Lw+X)V z2_qYCC6C4)(Rx+)=r-yQ71O#7&~~qW1{}Lrh-4gmhJB|lxA6A$2lkdP(jkh512U(P zeCxcWO(@0+Wp%v~xf%7Xc7H;raq9aMc)&YY3>j+(*|O4$8qDae5$03d-a2d6*&kw> zqK6^`rn=nFDwLF}0=#-GL-Yt_faSp1jWxk--_Xrx^99qq?F-f^<{pqSsHPqPs^nwR zE+dh@vy?Rk);=FQ-prx51*AR{={V}+$M1~v}WJ|b?X>AfHS z>KhSB;v)`5nlN9*!$yZX zUNfL;Y}qSuS`!nOAV6f~X`}`2J&7yu03YyV->jt#3ztIV*5tqyixw}sY57forX>p? ziR=1BO-z6DIL>dY*Iw7OumM877B5>E;5qPRlLO}zL84bmBny{C=w#8dWeXRmAP4N+ z1U4+ZVd=t!p7QGIS=EyRGiL>=E}c88HZXPW)JrR;POB^rFd5&zhu=H@E98PDR8OD_ zH%r4`yq8fn9xwC34*Qs@&PlSF_?;tqOlZ^>8Ycry+{tmnA^tP&oG?%P{(wyJ&Ple`s=v%<&LBPM%l&A7fvW*hUxMG;P<)7f zo8iqEWKTI@?nn1(bQA;XJxlcAX!YQSR-aS=m40x^b47XWr8U>gMBg&Aj2B3*y=l?n zh8w6l;YFs#=4DGGp62BdUJ22(ngNz6)O`1d^_GSTz7my_Hr(U64+QANc=8aC_B)BN zUkEkdS*nIQ&F}H-fjSL|{v*(f@Ls1LZjKV+W(?dgoO6IQpGbsx7W~kC4v^;O5n;ZF z2tq9eL(Gd!(4i=7`u73TK-A6GEx6&Pfn(zX?=6K-es282g8V{tZ2VKmh$un6`4y_a z<3R7E@PSXiM?z`C0qemvFn?s^YvWh`>Yi`iJO$&>Dj1lfn)!El1b+*jE!b^NqG>Pk zsXt7SUC|PHEXSbQ2`h6HgENP(<=@lHnTDBVRv21BwMem@2Q3M!cwP}^TFv^M3N0U^ zZIa9b#?k@B`%mBYYC1;J3R9av$U^N1qxhO4m{pm^2ot*KGdv*C4iA)HkzX@s9;WNf zyn$TLcTynV0z#~7;GvPXe_=-X7HYa^U1R8QJ9gwF%(ffcd6K1L!^VhhynuieqZ+qs z9dA0WrNal=5>pA!&y`K7=+bOoys79l9KitOT46Wna_s%0bpl>=2%AaYp6C zrK#^B4+r&uEB0N~xg&AN3om_pu=zyezJY*ZNBchP+Y{U4jAe3ALILMC)^)rZ5ybW| zaP?Y+zl%3Qb<*KSKN-USPtyTb!sAMMj2%7jVc%}vy$?X=xY8>E*2>i5gQsL7vem(M zI`K*}-B&6iXCzA_t^!fqPk-0rAV0`0{hDV3e0hp97@ObzIU1MKSGtjA)-8CNM9R6X zXkZ>bn4aoRLQnIP^rX*vv?Dy8!yuA!8c8`tyfO|MDL9=#GssQhy>VDH%!XN|K3@WI zf~)y8a4?RZO0*r!N+@xqj930^wZ&jM43G{hQ|Qm<(qGUqM#Nr)&p`Z2)C`{Hh@8e` zQ1A#^0hDeA?9098a8(GiilUp7L>_w+VLM~1ke#-RPdpcEsWP+be!=>m?-=`MAenU# zX|D@2u3mg7zD0aTpYE7~KzPXW_oxw+xuYCF46O<$KB*M8%6U5!Z52-6;C1*YCeMm| z6I`owmZ0s+cf8Z$!|9$yr+bLFF%g}FGbZ|!j-U#i6J79*dH!s)b9Isr^X#PHnp!q{ zR20@URjNLmv8C{!OWEys3SKVQ%@#ke$kZ>=sC(>flT-FBPF5bZDdkatKvf2*h(4{8 z=crdCV%zXuV>Qix_a5M!N{`@4AmEJ>yZK13+7Lu@Q92&p%N&6rl$aw`HZX$ErhnpE`&XD+Uh7XgvxYxVg8H2S; zCUmIlw4_xg-)nHZ?75f>M@a^8hD`6V}iSpqWv${M{(}fJog? zp`h1FkxZe(^mp>r;@6wepcPOxCRI(MYMVTmo^*XxD*CN+j6E}u zW=)IAd+{wHXDq{kima*&+nIp|F zqiHw8B(6lZ$Ccz5N#&Q2O5JbkBIy$X@4SXGyjA%Obl&A)1XHGWXRsZiVJyS=5Fa%f z>Q@fRi~}87Z#pOIkuRk5{^OJrc6P&&=2g)34nf2o-JCMuR_|vy-hs&IR?lMeX16uZ z=gv6t+rnyJNcTTw=zq{maPZbKILoM?77qujTe1=s4O+ zWZPW!c?Q=<)k($|NNke%N{7fs8Z`bT4q*!eyIdw9wi|m^_Lyu0-%O zVrEK%`0z|9;6lGF*~m?n>PFt*H{VnKQ%^#6>?m{xsjNgBHXRXR3pU$Gi!N0RNpN3= z1?AG)EF(Fh_*J8H5Hw0sRkwwh^`La3oq8q z#$0P;wJKKRd=rgk7**DY*{Wc5=f>hyg?+N(RfX#wjw~C9vtvhAA^^^=vp?})V4FC7 z5YICzfbe5S6R*=?f1(w@Q9?^-Vz-f4sW~j|aEC6~>x|KpNM=>f%@RCq37y9i2vkm( zjK9_8HMa`35Njd}o2PiDO}~Vi$_Z0Ef!gYdnp>w(_{Ah7(<% zs5_~*q~Y`>i@&=3hHE1W12-(awqeo2#gTyen3@*M9scQ0ou*2Ar}X#5OCk%;zhvf| z@yjCDF1XQi{(>bp-Go#m6Zk0s< z_i7L19MQY`498N!f|YVd%)^iE*>%UwigmP*k9Pd>@niTCsNn~9muQvxOFRC)Bcqu4c?=92JTdY5tptzBD;O}%fY&u z!zqhrEPgCMmNixx17!krB_enh=zeZ^uHMB|^M7QIhVk-aIw%K)X<;4kM?H_dx@M_z zQ(Sx2djLOIAA)*Zihd&0tV`E^GSo%*x$#{LHD}ANej3!J__^*cgSsL`&wY@p6g~S@ zPBC2f*FjyMqQ4R9#uPmpNpp&R1=KAm`VOeuQ}ia(tMGHvcNf%aQtY8je*efG*SEzt z+aC9zHYP*U<^H2V`iBPTw++(o9;BCzm<67t3$I^Hp(%@(-UOj3ElU?RL2e2l0+}hd zQddZbKw?S@om>dPDOzaCbvI&D93tDVRS2=|*WI{yIl?ILG)Q@SO3$7LXzTjrTbTlr?EFoiq z{yr~QA$Wt}O@dz&Tq#HvH~sYp-Y@9NREdfH6~V)Tr=@9s>?i2ol>>i+=x-AIhTsE& z+XTrur@t2jU70EGirzryOM9M_qbwGS81Q%o%Rc$NxO+$Nn4l|{Jr7|p99MS9WYJF( ztQNdduwHPH;BA8U2yPVox!~)9lu^QZI4b&K7=IXVmf+_Fiv@W{k@lAfRtwG->=Iln z_-(=a1b-~ZagO0UD@Yk7)c;A)mG6Ew22q-SQP7q1UL^Xdf|m-;61-OM2El(7yhCt} z;5~vH1zoxC4~hO+!9NPVF8ID61&%R&pA|e;FeErhaEjn`!G(f12`(431@97cWtwak z{qutF2)Z&%J{J8jbku$bj>EFW>DE#zq zl&|_!JOMsM9kkYQ05`|pi@%S=R_uQt%jwln|LW;?f5StWowQZ^1?KQ3sJRV2z#5Q6 zx64O(kdB9Q#1Jlkdgo2^0^}t##UeOW7KB(vHG{iQ2i`!$yd2kg)t)|Hjl?kv?(SjB zRqf}i>ym0epL_gzhi|U17Pz}N7yJ3LNdGM&heT=4qO5^EecLxw@8`$IIU~7OS3FYh z==*yPqW)!LA$2JhKmf9zpWI@dSrq;E2dUABj83zW!%v%r{5_PJ26?fBJoW zw%U{I>)%h~J{HX1v#6klBgrV2uey$KP# z$<3PBR&3YAC$WsC#eG9jgmrqS#>q)n+pUV#gPM1;y-s#|n-SZ67<;kKs8aY4X3E%R zsCzTk;V-}5jP(lN{_O^0amKy)>$e|8N9<&*fx1-hxo?EhBOC8XF*|q*+h%&3eP&VH z=htjdY4*IOK8*dU(5 zFa(4hRBSl;2lxme@~xIzIp8B)4Nkx+WT5TBlkGtxp$K97^ti9r-8iP>q_61nj$++V z|~G@;-5LNC$=>{iPbd?%H6Vk z7aB@Z7}GXNqT7A=(Ud(cr;pd<+u?^)1Gb^+Vjvg)({(W}6Jaix2#i>>JliG><~d_xKqg3ur7A(XHA;3|I=i+M7~N@OC_klsi;?$NJEg zT439^%TX-|W;@lE_d%#W#+L5z2kG~TzP+(0P>4U}M8#>MLBJxVNt)#2A5{)H$H4N%67taitijQHAtz(iE zFT)($0Cn4igLyEjFQkMH$9QEb_%BKy&!~rEgyW2*0^!fi(owQ&nvl{StxxbjU-?Iw zQW1@5UWR5lfd2w^DEKc*Fb(-GiWr6eQU&)UGWsL`rJnv3|E1asYEax4OW9f~chWh7 z=V6ZAK*!c7W)yw3n(w5WHDHD`!sH~(kk?_X2RofUVTMFb)d?NoO_VPmiVgQQICqbU zKq?btOOS1!Opu{zP<$d2L_a^=>qQn)m>@chPWnJZWP<20dofla8*^PI$lUz4B6Qo< z6pl|;?XPiNOL!osg3jwNiQ^svjwG7OJ|4^>@fSzI0~s0Jo8(;R0gO#63!x+?g3|vw z%iMTi8>|>lL+juzsDVU#i+(ej7b>zB|*4Syaw#lE z7Q)~^C$c3(_kRM10ozL0%{-C6@LAtLd9gD14dyRAkInXa%#$$PSN;uPCVuCL9$QfA zt4#@u26V?S4?nth-OY!)t*bw^~6>VA#jFSNq|OK#8S@ngBL ztg+fjmI;)eLx>bC8&KbiAM2IrT@T!ZpBq0{ zau25He*pEvDS9ZA-#@~y_^J42TPDBakz{C^&UOsaKRHO>H%NbQkRJRBZW8?u_!SEZ zz^qsR7DK*bP!zZf3eBkigJPn~pa7==^4%wS@JcP&6nJv>A`c&)E%K0k5%z!^G9lk( zTui`IwP0LKfVB7}1?Nwg2!O7ToQmcJNb=v$#_*hqymP;dBQWtI!Ks4t1+Nxt5d5kj z>5TrqCiq(*-+|jD`ririND1A2LC}>I&*z_LK3niA!R3Ot3$7Mavf|?)$ZeME|CsD+At(PM_|F3Z5!>mY^#O z-jxAgE#~(C(}FlVO~gRs%69*q*q@Ft8SXiP`GPK=W1i@*61-k;v7jyZeZgM}ZWr7q z=m?UZ!FtRCGTy;_4VRyBgV^6B_%%V7zhQ~~>w+$y<6hDKKybU@UO`tjdqVW?yS7I~ zpN8?7=^7@OEjUgvUvP$?%jakkeMGQTuv73(L6`60zIS_{m{ZsVdLlBQw_!L8l&@283>?!Y< z?#>YNvji2t1mRDBp5cFqi15p45BHUV)kK8HI~l|l!Km2ZA=o3hR_wnm_-{nS^Y1{$ zLw*Y5ao^MZJ?#-+I>uz;X9SxY8kTPf5&-7 zs2Qiys6SekT@ywEtX7p^(6?}<7J_eA2LtG~aUv~;0C5`xND(C91}*{DatV+S2Ixo_ zkm!tygdK;CjyH^sLq-Qe!l`qJW+}xv-!dgJwh3E3kf@9pY7v7$?~oTt!1Ze;0#~&O zxVlNeEn1zj*8!gt10^rlA%=Ry(16?5jfkNMF*GBFL-Y=TpoF!-gKj999j|2~Z4vlv zfzMV%8>bUUUL@14*`Oi36PvafDm9n$KlM5H!?d8Wp=!k*^$WXcvFR_wm&pum4%)=V7L%kS+u*;xtCp+tdhoD2)g|KumdMcMy z%oe5=(BP0LV#RgXOaQ<52jL71 z6(^=n;NKZQLbmEtvtS!_1{oic!XTZ|h|7bx7@d;8j$oOD;%j_uS8#ufNrD}226t@F zOxeHGA~o#kUX-dzGXh1*IR$$AOWJjDxzBto`XUI0!Aro_9V{3~+xiS7{Q0{g=*Ci# zfC^(^Bu|fZakw9Mk3&>L>;;2>EC{%G0tP5q$fUuzL=i|Gk7q(Qd>1s7au-n>zNe#< z6$xlT{5bLK7(@GbYX4Of0VC<#P7QYPE1Hw{6?Crro$U+?w<`3;BP1Z<%?*I?k7r+2_ALtjC$-o{FOt&Yl)cm+KgE0r^hi(fanp)#HJs6{ z&!A{sG3VeuA+03BxbGAccLmCan^cHDRO%KUT09G&7+Gb8nfGu%`k#=$I}J&5`cew< zH*iT}r;p<0nQj?ALSui=9r){LIWgc!9Zd3@AU&$rVAnyCqSy41cFqe*?-t=%ef!m| zj^&?6=qy~PY^+D`{boc)aBsiYxQivl{Z^(P`BI6Po(b{RFyNEKPM@16NZ&|FwW{-I zRLL`@e@OJOv+oe0ADSp}OF%u23b|a4@faR3y+(1;$|>_BCC?Cp4Eh=a&U&ep-5sv& zKDNTg;Cjn?jwxq4Rgm^kjJ`QEHQXQlx|=3V8dgO%#CP!CQmHk~aP68NF|G(7!jbw4 zFJwi4m1#xpJO-LXz`yXQfVFRQN7Pzbh_uv-e9JKR&YTLVaZf;agRO=6=-o^d54$~_ zpO%Ji-Ps8J%E$PZ(%h!z!1nb_{b+F`>w;a3-WsNiU-p*n@pfM$TVNyCkVsSE9K|G= z4|1dLAsvX%KU+<@CTWq`%MwWuP+`OfAV0(h0nKC}Wt7%DayNQbp^7K-$o`wxJ1a zc8QJaN6S&Kg4~-wz-BhWIHX+8%ub(~1zi@Cll>F}W1P62X$CP2;wBWc#;O;wp1t#14?+w1UAjNcr9P9;v7<`z zZ{5NCZwmN3N%kM?$n`m}!T0!XXBCM8+J)4m!pKsUtr+1Ei}RR&n1rI3l4sITuI>_f)@n?EwAc)Bf(I=-s71q%ilj!8%kzwT-DcvcQ(f>0HOo78d3@ zDj#oV`8U87kAd8a5Xt1NW0PGA4ZX0?>7JGYRJdMIEuRQrp|gC6ELS4^5$TWRF1KIs zq6st>c$(KR^z0z~;7q{L_-DG_zy(fT&@8o$yR0l}sMdVr^6>t)i_Q1!%e+d~ zpc+5Q?mULdTN`YL_qcC6nmH*PRxJpsa!LQ^T^@k8kn z%sm{!{M}cnNdS_a4>@_=mm`$ayvp!-LDw6a(q4;J;Xua+daTt%gz{DMLUuhQlfkrf zHuwW@^8l=zoN-Bth;9{X;7CGCwidQ+zJ^@J7dTcy!&+Jc;}NVg2SS2ki%&gnYGh&(MpvRbo_`6$xs2CugPlesbptYb`6XMCu z)=`F7+EXEAEHm6^Zj0`g+Dj#t%_-4bor!2d$jLf{#@M(B_$AaH1Ojnu|H4&)3h6Bg z3DrPeHu6!z1~-&$rB?MCCnYLrd=Mv`Y<_KJ?lBI7LmS&deMd>!aldWh`XBPcz>l+Y zWLa1jgUUjsmj-q>OZf5vtx1qOPE*aVKMMmW92T>rZJC3j5(M%@(IHf+S zXlnQXIO2Jlli0RXBtKU8uv>nv$<02=e;!|eVIX;EkXV#*zOkJ5G`V!s7eA2)YOK@P zJC$Lb2(K!()rx$rB~6g8HXARRA#ko@@f6x@!@r7~tW}Mr2v5%^k`uzK{w~@%7n$6O zK-^0Gr0R4FI;Gkqv%27d(o7&>JTCMxfw)V_eltzN11?dx-2$Z^iFYcpWc_oBL=8{6jZe9cgO z@RK<1bOti_G{Z55X%X_ch|Y&k`<}#+uAE^AdaH_MxHiF3URnzJb?qh-$5+)Euf8YX z<#Py+t&8F9?t6kk=-rRFFB9EIsJw5llaq-|b!?+R{@1WM6l&wimvh-I$J~F|Yw)mu z9}p0*7tmpbT*)Q#U97Gy(jQ{ zk7p`z9&QJUAP2)>nmb1V5#6jEf(8)cy9eM59YersHmq?o`L;sa3|(%)7Tfm&JNr<| zc~LKV7)e%|Q?`@S1s*hf6~h$6(OV{vNBPK`c}5VlHwHpo6@8{7lMxs_k*;Mcf^utU^`fDCC5<-=kIH;Ag5usK!?1Vo|sl2u#HT1ajA`u#=A(u=`ylE5%2?x?yIY#tj zw0YSbBQ~qK1}EB_GE`$F!f|d6GKZtUSQNvMqDVM|amvs@2^TG#OprF_p#R})moC|# z&?OVf;D}tf5YfTFma9Az7Y*pa2c!ogAG3KFF1Tpj1hhks%;BVe7u0mS8pwt64&??* zO!(0g0F**KH29B!xgJi~Z|iNB#?0`WZPTnw7_t=Xx?Ma5&3+JlLrQzKM&ji+dxqCM z)%;gT{AA}5K4d-~{ckCwl{=acrV`M^Q8>pDHOTDNBA zO~&pm-OX#f5J_mfg6V)XVLcW4GRq&9Cv22hryzTr+T~?p`pcF7?8YxA{bK9CS{BsV z+S{DQ=A$&`lukK> zwdCcS32x)9+(sj88q0*m-?MauDI7^X21k>`gj$VzWt0okbyXnR<+-d|glX z8W@@w3~LgyMfnEwXeehR+08)uT@MfR$i9uf9tJYSTY*e5`xp9SXU1szfb@3|NPkQQ z{k;ujRD<1nBpxog>7G=~&9WenvcW2DK|@jM7*JP!lueg}~58LrAdknUSi6LVC3 zuiWt`GtW|Dlt@f9`$wBsRO@Ue~5F8 z6NS&2tVR3XlI#D&{_g821Vy*b*de_UARH96*E9-y zO*2p!5i1+(lgM=)N7Ev+I*$H1av947$>ipd&@?vU^?nfvn$n=+4NvuBvhp70HFdkV zd!#qg^k#cs^ll7cuTikQp5U}cwhwJTyh%^sRL}+|a9a_Wjpua0qG6CDB)~Hd|AY&8 z&1IQ48>QJ?g|35*lpAxe1LwHIKp=4gM@rm$;T!^e1p5$fNp}MI2qs7Pd8k+1C(<0c zYE6e&^P^)-q``N}*qIm!IWF#c1->Hc832D*3xr3PCzj$brog({o7^>vJasJb9Aq{l zyN^JaFn}_JGq@R=IPb8lIu7}_$WbFq$@D1HqZB1Fb2M<8^2UxlpDksdOU zQc^blpFrJR$Jzco(G{p|=Kth%eYst-6P8>Du`M}9kt^V+Yi>Gf6`UeO#tM$-T&$Qt zc+nFUNO45oLPLrbl}&axhx()IlAA8}JU%z98kFqwF3R+N9DWURjga{aUdBYou|qC% zK#K!*j4bSq3BS+f+BwE)poGWp``rnwJ8WRCMn7Ucnfqsqjm>1q@I(4Aed)pb6Ia7F znZ(==k9s>u@+}eQ)zpKsr!G3dmH$=sw(gQCb_f`F5Hw}N?`&7 zy*e$8wJlMSCQ3?^HifiJoAgDE&_atr1BCVlixZNRBo2qulUC^nItb`6GgVPh>VQya zOAA2+7MM5-xtAX&FVWDeAcK}VrVDE2LB{EXSgu~IS0|*lLfEmeoY#D-W(ui^=uWFE9 z4b&+5HlSL#w*p7T(%i^tK*O2L6yA1+H;s4g>=Kl7R^=nU*8|0OKQQOlqENnSzJ+B5 zJc+jyu!?SmvUNGB(Yr?H6t`&q3>4*^Kut1;m#R#Kn^AGJFx(*Ch5-DF*lR6AO@Aui zSYO$J&>?#L9ZQr!K3fMl5qhR~9}&qe@}}6lx^AfL1ScC&OSGV{FJ1Mk$iNJGGjfAm zu?lGaiF12(O)_g+G=|%cs}WO0BW%uThHaWGAXk?@T>ksvf-RAWM-tePwa;i|?Y}!Z zLjFPMmuJ$ZoTDT2UYhxyX{qBti?K(Ri1bD8FfrLO;Fo2#fFS?cSJnG=mJA%xo!NzJ z&hp+?taJZo#2Sv}D_jxkggQd4KNL4DbJOq4Ir5}>fW*rn1l8kt0jP{$1FE`H%4pU6 zGAeiKqh0)=xsP?K%k@Qd`F5ax3U_KPU*=z$Siwx~N`F-W^NdUL!z`%FOg?D5p!e+1 zP+e0e6y94V+p>3kmgy(aSyq-CT(ZO?QqG1f)Dv8H^UCc3A=RM%Y; zOQrFxZ^%P&O#(U4z^0g&DVJS+tQBC`1pi%3B5LwZrgCWNs`xrC;vLX~Xj(k@R14d> zfQz3?a?%qR1z-@N|2cUc!rRQkf%grs8;JLOPf^*u;^|0GVwtcLGUt!|2M10x9usep zq_z+uXR_wJ=1-zVjQWeBSaovqYsA`Vj*o?nyn$a6WeQonDo&Iw=={ROPRLT7so4`d zIYWIKYC%84@^VA7#x-&WCQ9`5DdzZAGDub3z+^Mh5%2yB6a(*n<1>-;39u+uX(IJC z=mgD_pOtU#MmKwt+mh4Nef%*L{%N5`%NW=4ijx|2iEsUkK5;HCZDY;Xe<8ZWKZOzd zkHS&A*;|6xQ(6=gjt^+14A-d9W$8MUdwI0;vWcC#+D#*7e`FDO-)$H!VHsgfHw#a3?J--m$g$!EUJ%(abt>gnbaH9aecPIkF= zinml3B$`}nW(%2YR+-~BMPa?#n}VjB5q>I{D|e>q$;rY3zo8&{cG(jh??-^fAlg4> zf8qSjmWiERd-BVkX#X?m&{4SL{pTUIGwkWy^hC3xn6gex11Gpj`M11~zQ;-5Q*5t` zcmI@tXEN!NiADGVV;3AEJ%wJTJhHVx$AqQgD!=?USfg&L(Vcte;q+%Do3 zCQWWflMF;9G$b`urBW+fK-2wY)VUw0sm$4ZX8eO#YWyR;SaPsWrkR;z>f^zi#MNH) zn0eLikuw3LH!^rF;?(%3dnL)tkL;kyQ2?@qyo+S|)c8F%Jz-!XA^N3H$qdTt+PBQJ zJQG?JsoQYr1?x9*^nc5S^&2m3zMPZg2s4jG>n^=y{mhv&BSoD4KT}7}mCl@VA>Ws@ zUVQ%g4Mmq;ShV5NFNC|e=0-j^N1Fw};tqiklnX9xZoT*tgEcp@fU5$EE?>LhBHcYO zLb>G9nc_B&YX~m+;`$AjI&2rbY)o+N+6|xOVuB*e8PLjcbaNy1NRL#hi!NSYBw=T> zXF<{qr*Q3Oxv79d>@M99nK%46oXALn2z7~q(?oI6#tYUqa~VU?+Dq0IjS$Z*l0L`( zh=)X7Ty)XKA}Nx46VAWFT*v^w51Wt;IH3fNa>TD+E^Z_d`?d@xZUZf^qxk9{vdX-tb8=zKdQCGoQZ?x_4?N z^ZRoaF9irsKP~SS{@=r!1&;X7;ZHyDJ4ylWr$_xMBeL;yc-QwFjzAHA`X271JCL31X`!M^q2t1mQqxh3-$~%_6kK#9rd{ZMU{Du6&_Yh`>|F7)J z3;78Cuj~UGO|Mjp{PNhn8HOxK+I?bLrxyN{?!xc|sCUqYe|kqY zAX|%R!6@+td>yC!294z2D7soIksJk5&>m9@Vv>?;&7r5{y2el7I z-#gv+KT`m8r^FCY^ieWfQ2RxMrz7*lCnHE^WRA3OEph73hy>qsN5ouU4m^IWcMRk~ zL2!PdaQOA>9e%$TIKhh2QMpcii{e-S^+P z@ZUT5n)^QFzQ<0m@=bE^AApi?h9L6IW(A@2b}EG`_c-=s2=ZPIRJ!T}(bu`|{Q?Is z28z#>g7CS7y(ziqE*l6+C2be7~h%>)_{s z;&X){eBS;5kTgu994nuu3KCxuD7<1p@Kjcsvo^BKo;|CytgN)`^peBvW0^f?mf1=F z_xG`E`=BkzB?e5xKVz&}Kf90RRzhfq?-4k=pzQ3z_?BY3Y|{k&;CbBfT~k*6{>GpD zAn$Qqtha`~g!YWo(g~^HBYl=Oh|PVE4z@VB$wA|>z|)8ir)jzE0$+$}BDm-EH2sS9 zkKLKew^8d@;9q6V!kiUH-p*ntt-g^ z(_gXU1N|@4O)zs!rr#W{#IjoyU>+m3bV92OHToDtzd>XK%%lUaITA2bSN27*Hzk+s z+eQ_g*^`w2Ab z1UvPhb%IY|FI6mH>=yd7+RhZ;@;!ZIJB`5hW(+qw7`Z z6{NXnnr&7u<#R1!4eE-azNt&K|LW!Za;7k^{5qLd$c&ze-_F~U>?$}UOy|vBkca$- zBp?!ai9DB;{_*orQzBaSnDSS-`bFE9!wh;}XBey#67(5quYrDm2Q$yk)EhBy<%xe( zc=fKk$eJkw?~mwJM0vB$263rZ(0YI=%}$7o5ivijYyO_)9c9WWusaf8gdR%9^uy^k z7jci~8+(7R)nI=XiMwPsQI4uB`78EIO3VHT{WM;Z{8e~Qc6@qtHrXuFILTx>$dYX+ z`emN^ua+5QI|l2;uJW~tMV}Y?v8&R$|NWN|Z=d$Kpz4Zr;Y01aP*_oPalB^@_D?@I zi6%55TpZfWu4E@fWReDJocO>xR+tO$0Q0x~jH8w$R~P9dXsC9EDiB~(kCr-}}~@}ye0e;eV- zR6FW_gGspXm7Y}^s+X2ER4+maBqiGfLM6AsS{Mn8-&OQS%4!D3=$xHI0T^1U4)#QW36KbhJ+G0kDh1cTn z1hr-4R#<69Tv7^OQY)Vop3PTk5&kZNzdhM0Jm{`AbX&}fw(x6smmJp%AAZ{$o}fml z1%)RlJV9lLptMy76kkE%cLRklDE!qx@f8%_7NGD1mr4C=c<8!6CR~+U;WioEZgYpG zozjLdk&BwSrd|2Tgv3^zFe}R<*r?okB}EZ)Q3z@W!#1M=XHi5W%UVSdxt?(0TUEN% zF-W9$i6bZ#%Cd$H1AM7m%P0P($~Dq26I33l^lFuq7%nqKhgcpakUOD6%X%r^9nfq7 zOA2{CCpX@G5fAvOO&V1G49}WJ>ox{aw=Ce|VXfLa0GG}8@8Ii-fO$n(QZX;muu8T{ z^emuID-Du$VzQu325*;vt4PjHSSja7O6+A&reF>Vq3qbMLyYOp)l2=f8oj~CU3aK61$IXn~BN z^dKlaLE#B1BLqj>Q@C)42BO0k6#i<1AG)W|NSzU@UNlCvHzr&em1JmwMpJw;D(9Za zNx7$qBQ_PI)h?TgLL{5oVv4HDW6Y56GEjNH4GgWrkS%FuQBbxbn^IDh)v`gs5zp`3 z6sna?iLbs3->N*!ijl08%Io1Pm19#|jPa?!$vr90#lSA+K(WR>+5Nz(_@0h;zf6h{ zLkf94!ltatc%TWjNh|%<^Q=@lr39+?0#-eWt;uSllL<*qnU>0C39ud$P&!p+q)y=r zs=*PaOX(55%8Kw6E`0GF78`t(74dI#_%^G@`l)WS-D<=yjrgH0;tyXz@fB2l2#Rkl zP;v+guM;RdL7ANVllTe>|7xJ}Lr|tFy!uf!-WFq0!nG#lbYP1$2_949X&H)4ihOX& zR>4)2Q4^(eS7fnFN~QGx&_4kg8$sCn+uWS=3YIMrCz8MA}#1 zg`U)$KPXW3<+pjP;)}xHQrrHQy!E6rIcAhL2Pl>3UMi0Z3{U|DOFHi8`~GyZj?FP2BGe~ z6MW&d2@ihCHStr*geR!@w!80J+;>6w4MEWhj?}eb9US%n#@4Z+6Av?WY+oR(V;$Z~ zd0I8r>8k~_iCW< zwgJ@_RmKQU;mQC(m74v83s0;SYxuoJ-{CK)>i&B3J!~hBZ9ltsh*$Bc)Cek`I-uH$ zf|6GmuhJtZyfBr5!czthH=?{JR(9=+iH*sXuyip-<0=X@CRD(l)OMV(P<^|T(0KQC z{7=(T%9W)lA*$gbCgNR2VM?%7T(^O066sy|wGRJn*hoQw!kXesSd| zpEqI0fc3_Dy7r6v8s7b!9hEW^dB}M8ml0iJHYPce-S+N7LohxvRH18>U6D_mQdUrS zm+-|<;w6EKuo+md-uKOLm!d<2CWj!z;dT+Nyfmxg$}D32XF2m8-`rvTJt~_RPElGHvb&qgb6PKB&fut=+JA|# z70aN5l4Or$WO$EcYG(RCPVBl7eHp3F$`&r(`vvOb^Z~oLi;Fy#*~6*W8y_Sd9mwt4 zA5EV)_<$XDP4^>ZiH$6XKIR`af;_C-dnM{zjgPzb((;w?^odKUz9Fjr#{!P0pRu<~CQ}s**KYz^B`R z-CBEcE9r8sgj}obJ7TJGi(kA)m77_Z$?`bz#4+Klcb7NS@$L6*{>>0rLG7_amJ<6i zdFUO*1k-Vayp>OhZ+(&A5&8V174A0#Tz62!Q#$&Kr;c*xJjHvo3KBs}hhp0-;ylmb zmmkyq0Gc2PEEe4PA?SwnMIza-`kcD}ytM=Cu)^jVVOe)_W+dprD4HTXN*{x-P; zW+f9ynTaEY8QSZ}_t=*+=I(%g46lZZhu1Q(w$1np+1bg`n;*O0Gk0BMb`}1Va+U11 zH1vm{v~GfdHI|E)yN#J%@muAj*9%#9}UFYJU_RQ8Z(Zk7*km3jwU=I4$p z1qOxJ`4h_MG<{VspUNrwnRk-H+YkE38J_U)V%Pdc7HrJKX~bbZkTeo!onO{7lxi?u zEqdL*8H|(5x&Nf2(oN9ph9UPnm@iDmL4$XD(~sVTgf$C;#6Hh{qht*n^Xvr2U zdqXs+#pP4uTmMt>G*IEhzAlGfr`J@nX76uuyDFv(wXN~B`n#koIwiGYzIW1UK6jm& z+wl(sHu!~FgQZ5sGLD9rcs zdiHE8!!eW}y++}NMf-y;&Uy-svZZ_l2U%(TLf8I$V}8T?%FgI|H`gmkb||+R{1VN9 z)|Hjyw|>v65ijKF^7hsK$@6uMy<$b{jb7qwz7cJ(n~=l*>R1A{wz=q{OD3o zU(|e2>WZRu>r?A5NU1YcEJ$bh#w`yBx;T&o@h~i#D=Wxp{r+(o6m}kMZ=1 z|G!C03aXUO|7Gn)BIDLMXD_;5pSAuxD+kVEjrTg2tnu<2iH7wSu8aOZd?~qZA(}+7{!ndqP-bQ}e;r}nzGl#4EB)9I- zV40ywL-;OTg*w-FmPMNMDNOH5^Hlyq{8M>W%Q}2lwiIQ(Pv?0Wes!h3|8DuH-MIpT~0zf8qB4e#Mk zcC$Tv0qXt6G4DIZy#Hv-`>rwX`^UULGUolsG4Icfc^@3}{ukb7k-=M?{OZN*VV$h* z{8oCxMXDD>J~wk#gd5Kz8@XS7-9;B($o=XUa=H5FxLN)4T&up3Yt=8BS;~8v&}Kzg z)ve3aTQ1RMBy$A0j^uQ3xJmtUx}L;bqTa&CGa@Z~D%HyFmf_{&7c_nL;!Wlf^^NOO z%^Oqts*OmOd{$5F3UW_`QLCD;ru8lBTJ^N9m3rdybe)TS!}^OaUmy7=^rE%KzdQnefqs6B1J@nnXJWXyMf7ZO5PH|y z{JJ~%Q#fk9KZ7ID9m3x~+P=?@1M#Wv3iACATC<(RHYk`{BYd17yr%(mXUE3`KNN{< zbnu_`9lR}q;C)5m;C;ir|GR_V69n(a4&LM7{SH17eosJ;&+~Bvl6x|RKX)2y$OS3f z4{I$pzU~}sUi_8|67RV{#oH{1d^aeZLbcby0SABM;89d)`aZ|OG6z>VxXHn82k&rj zzk~VMsOS?8&Uf$<2d{Q;hl6)H__%`u4!-4JE{;z8KI&k#gXcO5(i+Y#TB9ZWhn$HB85 zT<+j`4qoWs)ee5k!FwHi!NHdueA~gJuyMs#;NTPoKkVQt2RAqvIC!grPdoUsgOji| z@tfh`Sq`pru+_nB4&LJ60}dW=Fyr7W4yvq)?}-i;J2=O|xem^EaGQhQaIl5#DDSl< zzhw4%ugNc+J%`o$`u+Vi`LAMo`l&uttr;8MO=JQh{YT&|ID2?y{pJ^M;VDgdqh#7; zlXgA0o$b*G)WDJDH8CA2GO`kO8`wGgb$sD2G@!MqcM41>v&-$`TYD)?jAK8j(CB23 zsUJNt^CMu7ChB_Y9k1~Ccz2ye)fl@!qngq6x54p>CkhqhP`c`9Gg55E?v7TZ-Db8oD9#_aSf_BLCmeWM zLwiT0&V}T8NIFwTn?293n&%^VwygYyqgkPTbi^KjM&JMl9s!;{xV;A}qRfB|V;s!F z=sI)g$|-17Z2O|rJ(BxKBX^in^tdZ48*apLCC4eQNMVyP7!3a4gnptC}+RE z*cpc)#_=fMwPPSv$;vz}M>qKt-Dihuk4TwK^@uNWOhH@gcbb>>N03o5$zuHIQ6^*Z znWXBuRd(9QH@mLakDaJx!5T5?*^`=%UH+2CbhK>1F5xnH6YoA}DpYo|e;~?r-(|2? zQq$3L7%A-o(Ya-RNf*uy6LU5KOasd#$R35oOh_U~>;!X&uZ^?fcG z1EUkdw)4k{!KQnzOLx5cE5wMbF914IW!Q*Yh|pLX^%JF=|D@1)*+z%Xe*u?*eFETp@fGXJqkTe_TISfKu=Zlrw`WWxMMRWVj$-17G z*fl|MH6`^dhED68*YKlX9WI=w5cTttg2IDZRFVgZwF^KBNEbeF7Iw6>^?@w^0i((? z>t#61B|I!mjv=}`D(UPQid_|D@3Ih>37}AF?3R**tkHZ|oZ6ot_B%y$rHV*Zb}YE3 zGV7^2P9v6w!ID+ah3UJA5vHkRmHeJfI|IsgQKElh&(rLOu=>a#74h7lc-+P%yB2@5 zn(>_sLK1fq#Z%LBv$mn#S^iA2sIn~W3^=~^b2L1?j7~(n)m8+k>x~0J)4N^oux|c# z`ioufuqNy~=3zp-`TMHSUCJ+RoY!aPLd-5DCjUGIQgYaS-Wdn)pXg>#(92}kxYW)Ye*h2Y6 zcpOCaKqlUO8yuLsu?2wHr-LNOuyZaT`kk&r2>ChCOpI$4Ba`5Y(Jn?#NB^4b4^oBc z=pVUZ<_5F+@!5k1p5tm4YS&IES|`C>C5CZ5c|z< z@Lwl&1ly3PC#)j({#FMMOIJa|NgOIXz$CYsVCsJ%-ZMvW>0B>)mvrNMlx1p(~5?8i&&VmVD@h!XzNxGn5DNQ%=jz{K4Y0MgP%&xX48#-{ose9Ro){F`T-s&!JPpK7Nf#cUvoEb}TZWeHP<9{Gf#-rmDaU@; zx1jLH@Zjv#seTRx!^7-1AVJSdx}!y3s^i@{Pz-d{dO^xN&6^2U|RPyIi;Leu!lA97HwJKo$=m1s*Y{t z0zv|3ot}8$r}OMlChR-QFXxOGYL(q&@kn;sqad9z)c%D@BK)RR@yWwzxhT)1A#sBL z#i)Pe(y}+1V{~=4+dNe9V2}zlVNvPN4A>-TCG!iXmKAP`_nH+WVa;a*8wkrb>s!;h zAV?AT4O64@&eoC0efedNwf}J2kZo*WvvO};%=Jg{^b`9Z%ACd8AI%bvZlB1JIaj## zX)(0hw%F^X&1#{`Hu{d1sa5b*A-SVF6Pp}5(HUtPH&H>h`wbtDQmKEOeU@HhyLQh- zI~IbXoPuV3YTf4>AR;77lPI!5g-9qSd zTz=2%t#dK9=fO*J=Iu^bEgpkt#tsViL4Js@+zo|y8*V+XQY}~&O4&@+L?g`RQ^&Co zo2qVx3^&t;xSRLi0C6(tJae)@e#gmm7k++_o;OxGz&8#D_AUCauGnV|pYG zdGA4auRn`yr}5@N;Y7cA0!_pTV3?v@k?${z`f0H`=DXXJpM7_2F!| z>`g5AH>Nr>d9Ce|m6<+NlBEe-)e)(L=a|EEbTVI6n9uSao8d~gJ)StI_&Hgm5p$X- zC9_|m>Uk)rxR&kTo7g;gH6$2Z4b7(QJnBc<6bf^73d@7hy!%^1xxtjPVNoXk4N*=VjwQ9hEQBdAv9O@$5rzkp7fzQL!avpspA6sckw1X*yDv0_KdzmeQbbW>B)3bI$$t zsDBLgq&K;vgw#r2@_!G2a#i>cMeA=DD>PM8&N@*DuKXelRKmQU`zOw@jemreGe$~N zUa0nh!Z%a_!}SxOOX481fZO2jm<->lynA}^4x4NJKO6jyaE$;R1lKaKtx|?hh{EI-D>Ks3H)v3)Nm3nE z63g~pSspquTS%urXshL3PKU@XI~4EElO3oH99GHCWNeMRsP!3RG9S-J&>-=Sb-Xwe6wd}`9ZY?dH8(ya8 zy~P*l%i3$+$@qXimiy?}dWO%jjHSe3jIfawTJFGfd{Sll1ec={Te

9ay3Qng2Ta zJm8q>BD%1XFAtqgJTZ7bhip(PGrC3-6_0d4Y(L7SgXRDgAF0UKd61!u=NhkcMCv36 zZBK*r%Au=Q-Tx3hQDXtwJWV;VjjW(Bu9Y6m`BALY_`kM~Oo{ATVKa^>4fJ5J2r z!-(mM(chLfvl#t5^C5l}i6HRp|=#~<2DfG8{jd<$YP@xNNf%0_P2A;q%qAaRqaV^qFb0=tk) z2;3T2o5ArOUC9Cy6_TLv)pXu)75^nZnBfa!7!|kq6B%HR*?jDqh!BxyUL!uar!>XN zRub;&srgYtBk8j?1qmyc-O)llFGJCAqPsKqXvJ<%EeX{B%Nf2#C`}9`!bBdu-RE|v z)&$WhQGL<7#lBBw89IApu^Hq~)lDd5dZlfd_sui1U{4~Qf#OK5)ae)A_QumQRCk^8 zl1^dJZd7|L|x~y!%)aC_f&a zT6;ulYN)8_FYLH`b?XtPbwUacf|;gQKwHWx#hfJCe?&HiYWffEZl~yj;VASGrX@s& zR15s*S}D(^F2Ca1pm>&7@m)_9p3;-I0-arpT+*mAjDCHZjbC=;!5&LIP?AG!mM-Kv zCgZ1%m08jbs0=D*6ZeaviX94yEzKluQ*yFloS{T#^ezn@!&%soH{9tm@$y0s|%^qBTWBaY#m zXy(uKBD54SePHlKL{#;Xr#8$;BhBd2bqk$O%l9{$4kAgZ$~?$n^Jwh_CB)4;*yFr? zy7|qUIDDx*y2MLd;Wb|o^<(9%gXDCbO5 z2EZH&)QZ?B(zc$SV_yWBa5p<50B>_N_2}>0|A&$IZ3yXVi$3$i=Lxc|nrdLDEj1P2 zXWmOiDYK5x!W%gQ)V{rXCXm0PN>*wB_jLT9TLbrh;h;~1J%vBzCq~aSrTD>tKk>Q zqyWXKzmM~mjn^~=Px0#SY=;LhzfEK06A%49#b5ZWcj1LH=so<#5)sxSjr^_w?}Cxn zVLajE@P~hovR2?`-dKua^eWkuE|#i{;@5(n6NH7oFy8PzgxTT$FV?b!@d|2fmYLq< zS+-->CfUh)b2z0Y?m0(N>DT%c=~3%dF5vt{!FQ(G@F}ck(RZCOD0s1h9KyS!#+b9cW)D4Jd!ICnjAtA3ogJy+eIV@FK9w!Y-EX3nu0u!0yI(aA zLmZ)`hoPk%M|ZvTaZcOj?dp>kF6ese$kY*CZwqeuob;M zZ38*k4j%9Agpi@v-anB6G!J7sq+%b>yP5cjm{H5OgH*ERPyZ3`zMkM~*eX-;$<`A( z+mfeNw;l_4e|_swfDf>J@ADv3EQ$C0mI5GzrSYBv_VN9Zc+Vp|&fYWoahjV`smls? zGqE)~h932@=s-;!IF5&KCSfy=RDxY+ zHzo^!Q>Y{gx_*hOen|~vkv#8`0op+rf zTx{yx%mTpf;}IrXE3HKg@9U8CLMjA9b8m|%Z%pxjX0k}+O~;UEUWom2A<0)aiKMqp zBnPS2cmJbE{>^kxa?RYMhZ6Q}|jDOk@n1 ztuWeMB?fY%p+X&l5d$&|x=j`u2G=J;21~?X@mK~k#+s60U~RxKICq+fzChF~4?{gh zeyc)5ecmiX{WvYJ-RB*K`tZW9E;iKLMJ*RKD(Qb;@)AS6Qq-4;I@=OYG?SXLcbDO- zD!ucnGSh|ph4IMB;VesUukn`DX5MDtefO0@mXisy#B!GP-C#>neVwL6l|r#C3@o~@0_;GQ%ouB{&yi~Yp7_f?ys9F zFK|<#yug2ojeHaE~%0qT>+#WL6&9Lb12gWie!WKrkuB}B<%^j+wGh0ORh)A+sK$R`Q zqf3#=;jkVFE1jK?(s818h;+~zd(_*kkjzKL_Sa+CmcEy38pT$#7MAtw$M+u0zvj#0 zHn?N=vtpHPisKV?Jt*ECH}HSv4u*es|9(74XzI?MuDw|#ci$qCZjrn)o+Kqr>Znc9)v305&sh;IiN3k8JI&njF z?-Q%hs#Bt}t1=m_cgHTp-lo_miDZ1~%5o{!?Gee={UTW;5|y?wvB|Z zGDRe^!o$SkwEfjbMbi6Ak^Gi}n|A->*jQZY8m$)RFN}8n^&rGNP04&q3_fxg2BWi! z?zq}3hQamEhYZ$=!5L#26p_Z!+B^V(cgFz#XJ(4zOp*L;ZN4CqtuKn?Ev_)!y)i{xKK(lDMRMOx&ZT?x5ecIe%$wSAfMMe=Ep zj5ek)matHn0Zv~Notck_JJyy8Ts=_?)~LB)3{ndDO+Q8BJpK)nd3yVQzWC4 zuUN7*wpt`NHHzdnT;{l22ThMs@_QRoc9UccB*qrLDF!-4>Ae{I4F|9;WUxjIel7+Y zg$VQPy)p=(nTtj8$FULG##Xk?$t=CwZxG2`k^EI8**@>@=hMxQ z7%|^`1qL~EF-9>Mi8Cxsor?30ZpHb4NYo)4W#=cFPE?i!{!^)UPDSQxLOw>w*`?J9 zI7W%t*{Hh;jex7gV2T*Lw;r7*yj!Kn^KX@a9~8+cB6$y`{EavdLTuuEp34k(f9Nnm zk1?HWPxySu;NQexrWlMaabY2KTD{{o3B6TCGt(jx-S{_3Q8pvw3S2s`y;CH2?-I$! zMN&DQM0I4AiQTwIB)$7Za->LV#*@euWHnN*dr%~IJS>tYUxK7=JV|KCVFnx!i9aBc zTST&YJW1$q!aDL%k=*!8kz57|BSb~Z0v*=Wv<6~|NClrZKOn8FH0L#)M@d!K@R@*_ zGU&SZ1gT_Esz_r(c0k^(%c)qGYOJVA)hxJXLie85*XjZkxvFUs>>wz%EE#`d*lFt< zqvOZr;GLNt8O85`3F`-M&pHc%_uJMFeq;8YyCRWS&&+%m9>YUsoA;~gF)Q14>w@QO zONjSe#YMOplmjJ_Y2}6SvIn?-j=`(X@>WlFm-4N?Nwa;t7)9)pBJ9CcpQ7Qeu<%6A z0(xYzp2u609Iesxufu4o$LXt)GzsSi;0!)BX1osxiXxfI5x^$Juo$qp@Mo?vXsP50OxObN(HUL~L}MBE>&rFaXW4MhO-71Z;YUn(r46slA098A#m6z@rQf7m z+!swEZe;fBjE|~i9|?9DI7VN?nT-*-@zGC0ZN^9I%md@23-$1BI6gX^x2sQCuyEA) zXu$&$86Ry+u3Ob~5OoIbz8-IK=!e}-VnWPux} zon*&pkG12plQDHUd5zPmoxo7sB*tlVX9itr|BrRA}Dd>(Wk$zaZ{cqWM*pw^hAjmRwH6?0$oBKMWZW?YasG+yk*hM5yJhz zSlmfjxU#9i$9ESCC-m^*cbXNbF*!k!+@TZR>p<1WaMTE-UgU&~wx{g=n25ucqKHqj z#0|*_b}Z4RrrVsAIkdV49v;FovLAB(S+3)(_BJ63J^?;O$Axy?qp z2}sAFeSxz`Rhsqz7gcIcRC3V}-8pzpo@z{K@~d-)G1`(L4xeHrP(@z~j~V=4t0 zQaw@Q>f{;%yPh)VjUX{=!8KnmkiUC(;?<|bx6TBqv#q2c()!EH`*|LwK2Fp(7>5&5 z|H)8a6H*@)-})*8iy`&%JP%Vp$&2&Qc!>xiu5r%-&Htac}c6v%qEnmFN{^_R6|oe3_d^Xqc-m^1lLwbXUjIi zb~Uya@0kQ!ydD^l%n^#h)JJR3?Hi02E+>K0_%>W0Dd$I@^t;Pg!*IpSIv!SrnCfT+ zky+2Lll??F>~S;ay6Wh2;0!)R{Zqhr1<_~MKaU`QeZSY#KR@7Ihk{C=Ww!pYk#Fvk zd0G+99c7-YKh?B`l-Wbk2EYd|1Vgyq$;v>c~$lDMN1Y&>gre2Em>Ms z9hpCGeob}#qEAKY!;rca^)(CT&2NY_5DlF8A5IIZ=hgEfFekET$%2NZwUMgoCH1w{ zONgv?1@U~UdU>R7dDXn-)x=p{zuNr&$;je)tCv?Vi14?#x*<}v!XVW1T(h)lcEml* zi7Y+q>?KQ=FODp)sW-5G(L!K#q`q!meSI}?yN5ZEdPJJPba~{gdCTkJ2w1p$=_K*d9}5XhFZNw=2tI4jS&#V)X)wS+lNI<>Km%- zz*t;YEA|Zw7Oh@64|c%%+IjQOiBuU-yJ#_q7siS@q9&bsuB~6Ts(R7Fnuai)k@|TH zs-*|AY6UVZ`cyS!)%8njS4v`Ks-QGmZS=cvUR{J#*3MfTsh_`Kc{RGNuUfP`LT(Ak z5GzxNuy!d)IBQ9jfpyClkx<_FU?Fy~T)76E=iq9=1&eBH1s7d%IoHLmV=Dz7_(c>Y_h(lnz(HCqUQC&8u`pkw<(T8;;^I8PHEPRgw?Ix zu=Zk3vf5xsM?M%PSoi5=*1qeOFFh-=WZq(OpKNPDJH|ZFfvf{Sx&)RlS!muCEj(-K z3X*E_cICXc308aQ^(cMbj28Suwrn^qHq~m`P;j#w#vPtvw%@+F)T*__Set z^UT!xO{vJtb!$^=BQww6xG{2=v!WoGJu~YlssD>-M=jE#8TTu2aO^sohd;oXHMAyG zQ{XToJeu_^A9U|HZS&ib#Y+Lg({BcU>h}LVyjkFg{~Z4G6Tgm-hX z07gg<>Z%j#T!-YfZgl(?>-d9C$6 zXS;6#`W^`v?U)5X8`j}JE{b9MlO=Q}AK)WPpLIOyP1zUh0lgBu*Y$-##mJR02z zZ?1!%b@1yBKH^{m*@ZXH!K)nnv4b%Rn!c}c@EQm2aqv|K7h>$f`-+42J9x;!859hC zKi9#V96adYWOT0Y3mm+{!CM`C*1==R6XDf6xZS}%2mk8ehsi79t#R;L2On_oO$UqF z<}SSR9K6}V=Nx=LtBdsg0tdh8;4dAVh(YRmjf4N>;0^~f4i@5Eg!dT-Z*=f62ctM7 zeLus&&pBw$cOv{L_x=)4cgVgahzuWN-IeGnfwIp}>7Bg2Uhl-c!+rm)gRd(b`Y7c~ z^v455f0Et_pW(vGU3j;H*SYWi?!MouaN_xq3*Y0y%W)3kR|8Zz>JcPQo^as@^^Tm; zDHiV^9GvZ7jf3Yoc)5dtgReL^ixpIgr_sSq2k&w4B?nKUKnriZgPVX#=a&RY|4tWv zuilaCfZj>h`%dH?9ZwfTk7Ypd+34Vx6b_&5g7End7k;Y?zsrR`Rd5m-sMW z>1rJm*ku7*1(p`%{G5G%w(NFbXx_6VEb$|n8a#Hvlj`y#;hUm2PyvAxqz)16kh z?M_4bOJ4A{8bo|mpeg^2UvV794Lmb;+X9F%@JHG-bmX&ZG~QdJC%ZWTloW3f|Hv{{ zKE}5mp-=XLECjesUv?&U0zjOKbB>q^6uU{Ut70zK=zf<#?-1-v?9I8+#eT)yvUju@ z$9sYQTjE=;777C=EK^UwHD7Vq#pd423_%qH#e+fNW_GTIe6Jb0@*}M8cZU@uZu4_F zO}E=_lsPhpy~^%tKgVAd^;Sf^YL@S(PgugGw=G@Vb^B6&8EfdS{1JP^3S5qOuQHre zz|28{Jqkl4m>oJ(qb9w*AEs;1wl5`={8mEQ75*!IY}$*N%`FO4lwwCJI><1#d{1vGn@l|5I6G)7TQUls0ypIb^# zGL+*!psg4@T+SBgj^kaf`i0w^C3jWaICSMRM6`}LyDFx07{zzr50h>a zGuhVcuTBKDpBUn(m|Avt^`5S;_Bu>4!9AqtF^4$(KPV8?;)&_;o1Qovy zO16c`m=q+o`MKnF`>B;)F40e6qc&HO{t@kVdK0}>Q4_g2Y(g@T&>C)f;dF*F-rDbk zX)`5Nhf}=($@C{lxh%`$bc>xvuU^Fre@P75RM-8kEWE{_WwwnloT$va!Pq#;kbU22 zEX5k6xum-7<0!fc6IDEATol()%&33QrXnaCG4%!x@~-7?yE!?)i|I&-gP-%(ncUuMNt0FNb-iitBCfYyHml=*$QSY?Ta&~}o?uvHl zsA#`4Iw}yAP{b@SMe!b9c(pr_{rnlV$y(3em5XK$@~QlsSbWQwL|lhN&8xI+LW{Uc z?3nYp*n=!{cn-{5jO~ zKda|(Uv#|ZCwk?gS9b1*g6vKy^Ed<^O|Jt{Bev*ABb|7*bx3C_7@V9}ILRx~QFYRQ z$EH-XYgLAr^FUs7QYCBug(Z`n37JxDE)*lZO1g5gXUMCVLJ?~ArlyW0CDMaesLKLU zoW2q&CdytABZTtIk4?oD5F2hlq=X-!>Ym=6h91L8|3Ay$jI`O zz(S)+rZ!Cei}>=+y?d@OksPJKubAe?X0Si`?6N0OX^rtP^#~*n7!=;SZRE~#yWh2| zV&YKSiQIWEMfs(s0NiTkC%uMyB16h(TaNcdO(EWmnRP36k_ua!vKvjx&QlVG%aJs$ z#C6>t>x*6og%VIq2H&b@eszJpgh%^>Qk&xZ-ubzFk00(YBJU{5DlNfITbE-Mn$ zZBEK$T?eRnPhGpE{LyVoig*R$$$5)TP;|l%ZN3tE$wGElacxDPI3TECq>Fs31}-3U$I&Vs?Lp2s;hlBP1*F^lxY6sw(g zMKpPgbYVaGxLLB=!xm-~{}AD2D>I63cTF;v!tzTnwJ*^r!n9_|v~Dnp_1Ot|gOh7U zkM@2v$Gew;=0&fSbKzR%o)7EQI^z*yQv?mM^23h~6Teb0iue(|a;69wa!`Uc6;)&C zv%IDvWM&K^;=SsXd|UU1I3u^F%SV+vzc|k?ndld)W>o&?yzCd}l7l;woiM}bn#s(@ zcuyU%z(B>>Yrb8(<(2zJktPwTW66O=s)c5-Oo5L2Qn6f$JEx*zlJ}02A+LBcTDt`f zi>b@itmN{Hj>+iyMZ)YcK=Ixu=~aN%si5u2n*r1RNGvr$?UbSEJ56(#)=ERNjRK@I zS%krBt%_}YYYw79oev12?-H>JG3qZ2D(((SuHB~P6n>nnFND0AsMYA=l(|064SbOjHz(b2U!j$$)U{B(eI2I<%W_7}cd5lNtwSlR{g=1n-FMK@^L|x!KdCjO z`*fk7IJThd8hdg{VSX8nl6dba5)Mn)`#+TRFDOaURpN9cHo`e=$GEWSqqw*DIc5E1 zc8%Ooe5=;#Y=f>;YE%I$>GEE)hwvFzyG*JB(n{Vn2PJWThCd~!J#DDGnL}!}m5fmVps(s9IDWN-`R zro}7wG891LP3_IuWtomok>SQye=-Lq%6craC8+2PN;nUU{N7>%tNIW54gGI>I(|s_ ze(m*ddvULycA#|0`CO>7EE9Y>r~Tp3Wm9kwriFrZHeShyT09X2$$OF=#@8iu&XM)% z6DjM~*~hyVGo0YXuA>>-bGjaFQ70u8GAz@UvXy~X*o#EssEUvVpBJ0jXDdQSBm#Z2 zM{)Ym6KhCvQVHEM&lj@xCxo)v9_%llK`-xqTF4x+X>V2a?h7h&+JBAOQY55Cjy&GGpJpclnK;^r z11m(FPDy3$#w)x7quRuWwz3DvUCQg1^woAY)PnynUL*c&?~n2z-Og93&nqwG7arg9 z5{YTXci@~p%}^cbFvXA~#6XuD$)j;%CtSV8AG5(4U;8?43JPf!PR30YUuQ}W!qC_@ zmGm{}c+-r=WE<((G@k^uQBak=@hyG%M8s927~rO|L$1(veAe6Ns*U+$*6BFq`VHTB z8=)$YJScutXT)5oo$<0yulAWkUfVNo)BRQED9QsrRiveyfnyHGQ zHu!2@%G7dc#My8R1S=2-32U$7uMwdvEU)-R3?!w5d&OUKiS9TLbs2x-Ecm>fpyWG2 z#S3H36UcHm$BcDG{iYLGZI2sNg5`c5aVcI*#;4@T?U|gaGf|#AgN*7AR_ z{iih3tgECb*2s%Ye^bfD-YbYtN-ulYi`^dYJ_=f-F0Cx5yt?8C_tJQ8t~?Ij#FWf; ztw%Y)#)L8Yr_WBwPzwCSO)45>s(b~)2C*sTl5>;CoESoePE&Rl%ITPHOci&J={Qs4 zf!gRx(9ks}i!^(sbY!fP@+z)JX1SJ7lR3oU>RYws@}g7x+T$WMJwHWqRkm1ef&xq| z2PN04!Z#kxQQc^&HY`o<-a2=`_!N#bRCqjiO}Ms7^_R((w<&nbYN~BC)JUhV`{zQj zR~iSYlOmkNWovxz&AeJ(T@!^4-y%QybxdQO%C&Cd%X!dPH|-Q}g7*$*0N-Gm0YT#K zAl79|cCZ`f5r1yASEd82_C~4pYuaBi*=Bnde&ROSG&Z?|59^Fg z?zCOGL@)VgY%*4Wb6e-ez_QyzDYZdtrnwvnDvt3v>x6XV9dF7nhrypntj4cn!8lV| zLpiLr0jG@%@Gye-*1Or8FkIby-ITW+ zx!NC+U&be!R_8jgwO%+V{0VI$+f-0PT781VN8lq1^PYrv((s;{S1~Q@a9S721&ph5 zTzkdXY8w|n+xY$Hy~t-8Wo=Y{Z8+9uu7ZASDE58hGH4DyG*Xz%jY^%q%ZsZwdK=;1BdfaZFI<6jG^`AJkm_+Yf#c_3t6mM|ck}*-!L?^{?)(ss z8klIr_$1&Pv~T^`?Kv`0%1!2J*3OwQ+wRZNXO$=0rp)}BwOrhRs79M@!sAvsDVal0 z8Bn9$cdL#Ev8E@JS9*{5}%dW&AL@~3ZQF$C0va@NBtB1GP zW?n^sUpy&DeLS)R#i&(+uhUp$X{L;grHCjeuBK(C4C$qkHy(BAdVw!_RY4^4Jo`44 znXdV47cK@3JKkO%*k0N28p+HtY=5NKXymaG=5l=u)nvZU);=<)8UD4fQO)kGe)tr* zlFgMkI1N|kLlndwHN*Rc$mWPw^%n&Fi&{d)$cyiFxPHkYZ-(D|DC%7l^=4cvuQnhAAVIValjFGGIUGBNrFD?_tJZ zt;(R`jDw%}tS}iB+HGZMx07&hSIchwDgF%gd`QSGkRz1Kml7gY6C+c=J}|%b8&Qu= zTxN+}1pTbCXK@*AWZfp~I(|(eU?FXx*5T3Yig$yOtNfF_ejFdjVNZ3qo5~ornoV}8 zzCY1x7!13qu7m1vP}~1(AN4Su(+|-(#h9}Dq^XaL>yM_5hg5&mo}6r)&s;g5KV|7* zu;17M6#)u0c2)B2%n#T>V}flp;U#X%Bo#yt-Blo&=m?56iQ6)LY%Xyq#vE?pJ-gh7 z**Ml5b{TV6RX;L#c7rhh-CZw3(ADW91`rmC;gVV)16U}(vD0>S=;mbJ)m{wCI49mC zC&{Rttd5E~oJJy$%gA-8ul$P4Q?b+$o6J@ILFT$L2#4-$(bt9O)~|$8hUV(t;U_-J zv4?e9r&`F%h}GJ8O+OcJd-YeWV_S}gl6@|(mjjpWa%Z{SS5!x2qF)vA!N8h%*CpUJ zCX!nXl(6#ja(YUv@QZ=Vz%K!gTrO_in-bYbxajJDE5R3iDCZjZH1Y1Af*bVyjf=c9 zzms2cgIhH*&M>oEF=l88Nutb{QdUs~hHLG4|N)tvC#f8=c0>3ELNAJR?4iB+b zN6Pv-)?uh?y4sR!j%+^xG|A7kuxb^$5xe4R2XD28)Cmh`4SwT0QEvWzC$h{g7{^|# zLfc3nsA3yloId!UBXN9CqLDtOA3Vw47ySj;4A=i6%1)l$Ly^HwaxZ0TTIqpvwhF(m z!PidEyca?d8Xk!*_uC$ctg36O)d^m75(!oH9nO2YMy{K#v9pWculoG&HPhH%jC=JV629E_R~hZ6%nsB8sGX!$y1dqLgliMB9~`f z6{XCQPUj<3swltD*4TQ91+}S#89_&ig$^c>|GC-iS_m; ziQym&nLIS=2-7&1Q=ESALeBjwo{lEF_Ui&9>GHtQ`QQ#r_3<%Y&Pg2hLm84VNR5p7I`zZ`I0<85*jyQv-h6 z=4cQz)1k0c%iT{MjYmk$Knh9eSEyfWnrE)NSbS$*$#=XG-GX&c2rG*ufaTwQOPK9? z@0bUUDZ39u{ZH&Q_f{y1ptw{+U^arh*xW@PZ?-2ZR{pXg%7z%U|1^wbNkSgIOYzyp zYMx!J;a6;PWwjiC5Dy*&Lo-^cCe=4l?5dFjRhicURrAyURn#hh!WUc)p1!M^wKbXT zBM4voLVr37I@MfdQ`>XBsSt~(?8GZ`y%X!|n-)t(#;om5lk?yuziIb>AV3qi{^IB| zzm;`C>xDbYbK6?E0Z$#-klF)zu~#_vNXE8+?Fx4vO{SNak5J zPlxNy%t_jC6n>3mDrp9|?)kc8#l(N-pSpAi*h9a}EcWT$j1x zS%OtEe_BB=KHmsh_+10ipXv^=~A2Xu`GP6$f0-NIOy;!SBQ?YFq5zCrBV`fyFgAX|S z4E4hy(sm8UX`{yrdtOSN8$`c{c4We{f>@qEsqELOc}AfXc|r8}VAD|9U%lDh6CEEQ zvPz{saofmvRnB}bcLBDiv7)!yUj>D9?HK$|xrn@y+`*UOG|ite{V&K@?9C*3$@1x= z6ShYQBiY$|AXh7;&Z#sc8~SopezFth=5K8Jn(u;zTx=(xe3=?ZvLY_JvujiAQZl}8 zBQRWnVo%QRlR?we(CVCtZbb^YxQ0AgLlNoJHmXX#PY}13*##NXA1TYH=r+ZBuU3$_bG^P<}7k(^YrNs7U) z*U;Z6jna+VI$N2&%U)tMakj?2*T8j6&*Q06Wk_}%j^S{FX>0o>GxB27q?y4dozl2H z<-vHb_8_o8WT(+1qjSJkQsq_L zs1zX24)JFIPYTR@NJ?eii&U?Q}s#!D@sjiB=q0|Hhp4VJ?DRk0&z;Zx! zrWJW!VQzXN&(cu3P^c*Fl#bLE9uP8nf060EU2N%%kz$8XcsRcBW0jWRbAEKzmob+NJqR$Ohvt;7-38b z_C&i%huRAIz##(Lv+`HPjEi6qBe?C)kc3_OdLnF{HMM_^Y+7R*wMNf0YOMmWxYc>Z zbG^ZHRQ#BJ=L~V8+iB7sB)&hYd>!c&Sv?f>5nV;9{SQ(D%uI?4zcYAE*Z$_=YA%95 zhL;R9yA^OA8d8|;phJ9+myv4Wp5cbrcv5)x<+bO(djSFtONAh0;-`)U}4>mN=DV#ec=2w6)|a%9&h zhT2N8&Z4vmj1D~Vyb?*WmWp%C%Pm&2lNSs(F7}*mY?O=n1n1l%=Oriq>h&Dn9QLv2) zl4#ICVi+)LoPbFxZ(k-rbyslXfyTDhy6d6ZdO!FU>Tdt*``+uCx!3Vo=kv3krP$)k_H4XMn?1MmZ;tifp_TM6I@ZXeT4X=p z)dRN#VqcBq=Z4B2L@*xn#L=FLXy*=(HeR6|8u1rWRKz`r5%(Zo)#eKO%sDy%xoM^U z6WlDVMZa5cgS+&99P4XXJ@uf8qR8gJNro&;!!&Tw@WAzqqED$K zcpXgI5;_BPBF2G`>m@j4H_SYa*-wvbzX&ncuLay z-)h`}Knjc`6fYbVK$9LO&lw}hy23K=EIWn$Bf9HboG|7PH()cYHMb-j$IX{xit;E_^RXnb-J zimb8pRc1^FFPJdjkPE8Dr@xD;QycQ~4Vo^PhwM)y36;nUZz%n)#QL9P<%ebz?kqcP zAaL#sJq7SF)-l9cbyRsjRx%Za&Yw|0s)(JZL1gvrkW2*}sH1mS)ft7Q2945z< zF4K{b!_kxDMLH72=|wavjojFos7FwyF@pM~5u{sXCh~Z|p4opb1_VYs#wh`*MbpDb z+mlMQ6E(3idTwlN{|t^Br~(tJR4>8&Vqara727apQPU;%z#Ww!&y2FN$9p8?dQh#G zMhkt@{%f=L*Y=q>AIH@Jol1RgfCR$!_3&*A?uX5GO=lNjBp%DuheH$c)}TxnfeCrv zLKg0Z3TIyHJgcGbEd`6*MOd4wj!;it!xhD_0gY4o&&PR~WV0Gwnch(PPCTxa6g$2D zM_BpsSqCosHB-QVeN_JhF8l|zOL%C3E*PbLwWiDO5blJ*f?uv$M zS{oYNl?^Lfm#zpbT>?=Rw)rbt8d~ccmak}VFKKRCk?)>5uCS=7-nL+I>vBjCSm9oJ z&GP2fhWe>+JgyiPbLP&02#LA#dBsb8;$d#}%$jMn7tWny+0Z<{;A+O>3%(h1t1h{C zj=Q2}Zgus{3J{w*ZgNw-+g)+twAm^i`I8&Iz^gKbJPF32X6Cf2X$wi<1peLb+RLhE z!e$cUKJ1$VF$fLIn^#`b=w8;athx0@cc9tb+JFpMwldJ*o_F!I+L{YhMh^2R+BtJ; z-81LRy<~Q!`{J1w&#k%4ec>E;ZRJe2L~PcDRWscu_Nq+3(7$BNKk{#tYgO}-#ZB&6 zkWw)5!sQ9YI~S4&nyz=QXHc*Po?^j1j`9OvSxb z7^cGnoUJPVSSH{n9YXJz5BJ((W_=btOK)MK`TtGw4>GX3OL+w9MxjKO=~P#267*^l zI6+?sbwRGp_6m^xQ7vtmaCABnO8sncOCY^@#PPV>jSQvzH)$as?dvTKkb1~N(3gdk zJcO&MZf^a&^n8661CX95|Iiv(+F z4u4mP{hMy+(J-z)3+|9U%JrcBFp&ByJkW!$_f{b3;6z0Ezl#X^KN0gM#eBDz|CZ*6 z=RvXmgV=u{_Lq&*_Dg__&-FymyF<+H5%Y({{MmD~`<=v8o9*|a|1*&OKO(~ar(e_V zMx*Z0d<+rhuK^jKx5WII!N;>9!WW)Y^_yRBS%L zIMeK;G(ju^>M;p!#4@}Dvvn_A;Z6$HQ#hH#)NVCAs+D&xX4f7#Qp;I*;I+4QICNrN z+yzI$YaXx%mS8S=YUzGQ&rd)Z?+`-(DwxKNEIS;S>c6_C5o&!{bqNl~X4$LFljk+2 z(d@Jdr`9yG{i=(RA#+eTU*|4Q{PYS$Jz>=&hSl43C~sW2@j;~BjZl5qxfXV5fpd6Z zi+u#VBt6o4G%q!95#CrF6P>SbeFetH`f!-fWl%1%$`i&G7-sSVIAsmm!zm1+b61(# zB8e~%yh9i}FsXcsU0r0Ho<}~X5SroBl=Ah%_K)x5~9L$ko4(BmQcy_of7gf6zoF*pM(Z%B!CK*?RPb+-Kcp1m_6Go#Lv+>4oJUqN2Jc8>PWJa@;kL zgvdF~f>}m^ub8FfSpPdNAt#tq#=i?Il=CCl4XSD6kSo!I&83Quq;Vk(L(dFKv%}_9 zOXsdS=50Tg5Ij?gmcxy$|1J>4D||C)sF^io&qOCSGcfK1i47DdCN%Ikmb?`xPmC1c z(ZF3l$9_T+?g>!UId=E98%1X+wzXpq(4LsvO!ky+cclUPGBo}hT z6HY~Mp~wck#ttdoZRk}{=2^5d!PMGWcJII~qr$09aXP(puc0i#Mv_HC@OSmRh`6a7 zt#)_6GDtR@s>Uxk(*B`<3d4X7v}$mTZx+)uyjdlGbRln-GZAK0T78U>YfSJXZpvDo%t7~S^(k!MP z&BbeYO)Jf)`QF>j4COLzntnT;NZA$f&nGGp$WmKnUEveykWGr3o#r`D6}vln&LN;NSvlqqUr$h+1Y(^+=sK>Imn z7JaA!pdyfklMi-buJ4L-6(Fz1Wl0|8`kb4CKQ%Mxob|;>zenYhAMMZSo9^yqrh!F= zb$_DD3hb5{&2H6AxZQypTNSK=Alh|3V|)K>T;DT_CFsYn9e!3VF-_ z*9dOIv_jQm8Om&a=(|+cs#C-KT(!;YWAYS7K$57+7{op|{kuqC1N=^_Jc6b<0I?*GdQSS?-7!sN>%*M5YCXtmC|{ z#Wb)?FfARjZtZD?gk ziLaKmlN1R0Vu!}GTK?ToGrgAH12sEROP>oh`w2^*2Q_I}de$Fzf*#8F$9EeOKgyBw ziosk|V6JPtKEiqX3zez|~ui%43B;h&1-GVO(Mu5r4tT&06 zru+}h;r~iRGYJ)l(=zI}3i8Ph>i;O%gfvmVmWXhAM88S&cMJXq$Z&R2j|ws!`9Xiz z2;M6A9l?7Ae<=8z;BLWJ1fzoQ3!Vg;r0WoL3FZk-5}YMiBY2r0<(kv~Qo&V%or3EG zHwiu@_>|xaf`1TvTQC{bnsiSSbPE;=P7(AA&K3NoV51=9uP8cCF+WjWt<5)Jnf&>+ z%cSBHuU)+O-0J(s?|weO4g{aB@40AmVxWx`Khc`Ew?Ky#$0LMw`m9P`7M3GCVTsU! ztgO4ycX;;GgXVz{W`4PG1S(P5ZSnL0aI1SAL7&rL)pD42k9*#t;T@jU1m3|F4n@sy zZCyU)Z3=QCH{pi3ULZ9h$QQLA3JW?0CBpj)L2jpN)?3hHOT`*YF>&Ff7le5Gh^Kq- zK^{PLRLPS!eMtzBa?%txXW=`WO5T|R#~G-&=uO{U0-*|c^@Bc9H3AD_j&L~E(i}iHdkr%5M8mXkr*N4;)1F|s`P zw~qO6>KwC=h4>FdHmaf*O^c<{U1U!ztD3k2QLB%7#>(sUj;;l82ltC&_Uu?HLyh)h zkrjVgzKiW`kUpG^?Rztps%Y)eL{h`4e)!`TPOZ=iTY!tb`pAx`CtF+vuwf(G-{ zN)NuaK{L3b;#HJgFsX)fwi!Bqjm|ZTVU8c_0kxRNg*8-_?z>>Hl~LnCKWu5zrui+qU*=j$2iutZ7%rfaQU?qCstmG|cESK7woUX`^XDnZiC z96FxiQ%fd8X@bx7s|#4*yff3L8EK|o9n_&=InATLuwoWYt%6VHzfP(u3Eb;9omfv~ zG6uLNYTA=ZclIVm_8qKvhpuf==K^Y#VW!^-bxX{?bN+#JPc#SPAYSY3++~MYKqI3P zI!E`n(P1MSAT?s2-NXy^`rzKkDuZpv8N$DQMwA{vIEH<+Q9IgxP_-2Vxt5XHqE207uF+=p3@}A!F$Yk0 zy6E1ySyg0IVtv2VRKcPGp^Or$GfwPTjp-$^8gGK0=JzRc&2hnMe}^*HhtKmDG^zk~ zbtWVCZm}gYgI=R=Rf)IK<$&r_SZB3URS_hASpOjp2k`@=YYwy8$a3MoV*&1y>ZP@7 zz0_51zop*=?trzo($`>p&0~Gl3tenjg`6huUA6i3x*1hikyUHj;E(k(d%90;Iam$l zdLI9(_SSzJ+l<~~F;6x|p_86rfJr945Jpf(f1tNGP#?VJ=xN62cta@QmB}Tj@H*Gw zpt1ito(-e-h#A2wtPjN z4aco`3Bfv{*5}kX+LjM%b?f^#uGvfeP3MabvOMI=6db-zuR_seV*bo^8%vo5NpIss z4=eS(oj{8QbjNQ3ezdaOQI>KYE#$Mju}P7Bk(kpRw&3F*?f7Gc6RkC}8`DlJ?l4wi zktRDsy0gB5q0`g29pf_Gokg2|ExY0C@9Ch|U=dGnNB8K>l(tQ17C)szJ}X>HZ(*YOzheE(bTLl+aXrp9$o#YPXF|=v)Y5+yYR2EvbEDLm zpl5lLhGow(w9-xblc0Cw$1te(0do`dGoWT&u>4;LHM>Ad&-HQ%ewP1*Q2X(-?5~2l zB0;|t>dFLt3)HL|mirr^uEx)z7lfKLEqf^A-@XN4_-K!D%UDkX1zN#ixk+LnEO55o2mDlONyuM2)8$aX<01dj@yga$_Y^8`x;`Ro+Ut^I|YMc*m7R&bwSpWr9JWSq;g za?t+>!7+m82o?+a1g(99D@ETb*dh2WL2Liud!m0t(AqzEUi7aCzA1P_FcotZ#_Mz< z^6P7&pD8#`kPpDo-3r0m1fLXqR&Xyc8RyIUMgM!j4+K9JRC4%1kE=n_oh?`+xIj?J z<%j(*pl3er67#)+F~Ro*j|(P`)O1G+o-KHu;B>(Y1?LJb5WGULUa&&X9W)n z{z;JY7N+Yz1apbmsJDV%!BW90U@|(+wbaAkR>7q-cdI5`zp~}?`!YokZeCcx^JDyD z9|r%Exg#^FxCE!o{QmL2jGY4wKK7aHSx>w#6NMcnS;q)ndWS>gG3kqG*hWx$8C%p| z2ByB5XtLO5c}@FMTNzzyCWdX67c~`bYGD4%%?!-acEb?cGrMTFP2KCZ_A-PEe4ScQ zVxq71EA(~;LU>Y#z-Y*bcg%hU+}{5j2A&lH%3=*sDUv-3&yj zgrKi%aytkF@6di%)7c&BZaeH7>5SV&TIdL(?Wc*BA%NUc`zMf+gT0aZFnmIKH|$Ay zKLCl{K+qhXh~HZ3gn#@Ybt@MX)rI~o>QWUb*2BN=6ztywa1!5weU~Qe;WUE7auNLU zA_AS;I*QfhD{u+dfxc5<LwY(Hq=7`UaOwB*bliRH(#2Y!t{v4G@9Ud?TCStc?as232imWLKUHMg^zI%c zSDH>o>3#?f6uIhP7e&yujBCi=xxp+zxC?Rjrxros&cwptJBSar$r$|Rk8Vk4^g>M= z?6~-fh$(S0hIh1a3mI=IkFTz?-;QmO^((nlk;_}BDbDiJ-#FHjjQ}~j1;h}82MGE` z2>GXR>0?J4V#5YZX*eEaxnh2RSvDFfi$5DQ>6-$39qTUDMDZvTZ6nsEs>Nd&L4hnK;2~~a9 zjte&wbX2wpl9fx1PaRz!q7R2rE*!Y9x8X(xdk}ewS*<{{{D@XrBF}@|D?=1iX6Q}b z(xbSBZ+cG&o@~4~{$oU-+R=3cIfH$lu2-0Y5Xxe@Hg_LfxgBMr`in8-ThF%R&y|Kh zH~({-D*FR-xlwnH~4bW{nG2`*~s<>Ixrg!SS&)s-dQdqmd%g?Y41bzN(A z{S}({dJ)UgCR|TIS{I?=uFH;hRS{w@_yS|*K-F@*Ut?Dw=6bC7%AkQ7zqXtT%A=fB3uaZ zi}0o|iWw9fQ5)RNR);k5;#3K8xd6=^XWnxVCFt^aLlMH|K0>bd-;TdQo&@--CA<1B z(~kaZ&8{dSrjErC2~~`l{a!d%au(`3#>13Z6LLO@BYu6&s5Eblqx&z|Mqow7y(L`S ztP8#YOVuKrAIFj-+fn89W>fSs;g9KFh^dxEE&WL|301KQj@Srd_8o`bgQp{rJ&`y1 zc(tOj^rPrWD9Ad<5#X-+%g8l8nVN>J-{dH-mC|1njPJjPkI3&1^F@xX_b^LTk%D8~ zx=m9tgMdLe?_w|%r^PWQlpe!B-sJ?it?*!fCND~0D?0>d5chQB?=-Ixx|(+L z%o)a+Chx!n4ClQ^e~G@fKFq~~tv?&ShVUG50}Yol&On0!&r}4B3$TfB5as$(-*1pj zF~nY#9v;g$16Itxe%@G*^$l@T!4ig>C(-;Ohx;D|2>B)4Gt?XR=BfSMLHs-WUlo^B zpK$-n|8M3~`M2=YXLBP#vDuzM#*nx9mx3<}zAX3_Fd1Q9jmkvcWV$79GPkOiU-S9( z;}@RmPxR3=vo=m~WT6I{Z_`e%P_d-iKs!ALMkM}1J1q+fYcP%pAib6# zQl__fR#T^Wo7*sb>!UV7w2`cN<@{dD@Ih!?^MbHi>|!#9A)*P1Rm)s0@eb2|@>r8s zz)iQ0>%)4?D&d>US_D#unae^@;er;vd8iLUwQ9w%O)Xd9+fUN~W-b_}L8Xjt@6f07 zra7xG?SC?e!Bmc(10SZU=;r?a(KF*)TA&a%qfX z)S63-oII-a+KvZytSMY=vNloAy2;b&$AQ)JE^TBaVEm#o-lA4SJgkmFKX{x?(P?kN zM2l|H2iKs%+N6(*tp~wURHESe4p>nLKLrP6eso|$mLCS4e@X{w#z-e#o$aXz=o2kD zaK(vX%zg&a3A36?eG5GX3B^)L5_4_!B%PW+*25|m>3dIy2CKudR8mO@p#)CAAg_qW z?>%Su;mG2Spcri?H(dY(-yyGv0M6dl&>N7}IIZBXZ;pzJXIvG)Q=*fe2 z%#>#0RT4YG%}_<5E0eB9$k&+S959@}GU|S1*BKSfVpvi#9KOtw)vZ(@GCCw{>C9gL;O zn1$xp8OB&-Nv)~!9Bj*|Yz3Ot13X6)GR53F8)q!wFHj@3lR3$%IG+OS9)W^~<1}FF zxF1*zhssFNu>KNWyk)ci+_LGg;lkHpGq@wtTkgx4xIvCMSw6+(i=rLv; zb2dmsgzLt;!O+a|6pG_|wEJLN2g?NFe!xhg`RFMvU-7C;Gc?OejvrKgRfykDL-xC& zW~*J)S(b$DrJryf&Q9N(-2GwOR}iTJ^JE$r>38*Sq$S@vQ2Z)&SO6E3lwzu<;^=;) z7mh2;QPXhPZ*lSa;h_I&Gz%?9LD(+5X(*y~@Kx$fb9BFe#e#}B#dV|^C+ii8W^mys zE=|da`UD=v1&xSFzo)QjxcUm1>@*q&90X7Dy|e za49%W*ox_#m8oWsr9d%Xpl%3L!?|iuGO!zgW8QEWFep`A-C$X>>meAb?GA)p=Lt|usNvja1oqkcM}p%Arn*PL z)t5xOp9>>I|F2PkSj=rDs2&(pT+vfi#}cSw-&=_gkbkaN(&zf$mE#V*C+soBRdA*| zY9p%vYNObT|NdqYjzkV0eI38Y5FHLi&fR8Uw_Ur?uKV8vn}f0q#BIw+C98x~zC$L6 zzq9_EKWFv{*MIPf@Bcx*hu66fk&oRAzu{}Zzk=^!5&CIPhtbWbs+I;ECwgmb$2CFX zXBW-zH6Y#9CO9N5ek@JWxA-3D?#rwJE8)(fK{{0P$C^TV)>l0&ewJMw99U|)rMoY) z2D}RH8Z6=oG)OCP4fsGh)_^eN8W2}sRsJ!rhpz$2`g1$XtuHZ7mKib8{GV9^TG_zz zA>YBjg71Mt4fCAzSZ3}7{S>Hk6ZGU;VOd-5E1+iUv-B52?Z?lGUp3TpW9b(_U5TIN z{tBq+#Ns3UVbBkvLfuc*k3>+BtAa7X zzX&FSwxTciRYB|if?xEtf-3}X7PR;b?twlTd;<52`GbPb3GNcyD`@c@ydnBO3LY2y zOfW4~$1h9pEWuTRJ%ZmAr1&qU=aAr0L9TF^ucrcO?-o2qaF*aw!RrNY7u+iNL&4_+ zExv<4h~DBiu=oseaI(tq&Jmm_I7u)lc$?sV3C091zJX(+CmS^BDLw(9;u8Q)6Z3Bh z)&p4{%S0a(yj^g!;17tW+H4OAJ|_5c!M(s_$Q8&$TV}XZ1?LK0F4!WtO0Zq8G` z4+=gaxLfd7f`4Rq7(iDnS=`hxxGgn!SANoo`5Fp~3yZ((d+v=M-NA6)^F@3Oop0A- zF2(B}U2ucBRug8WZJ4#Lh88;_71%NJY}&}S3_S1}h6g11R@4SM(X90FK#A|z z1u@imoFttTx>L#Y#ldJJ4dB^T6U(7eO^l5)EyWiSZ5z?w*cwq0xH58S>9v+MUjW~g z*}X^KKIZ5d%!wRPJONKqH$CQj!C$&J_z_;z()0e5&f_>M=mpKr<90{aT}qMS=(9Pb1fD#)q+r-yTP7^Njt`s#lMf?vB;HdYmtM{!yj3rjhbmbX5p= zTq2epJSClpH}WYyz>-&pWl1|ijjy|*FBzu)Ar@YV_SefQ5J#-lDA2N+OVQfu=3S!2 zL3ZwPA%5QZm%^%mYr=)|pkFvYZtd>hg9E5eJZ7TqDBz@@RFu<_c~JRlw8#jY^itbI z8g=tXuDvEs#BZkbw}A`_&slBGb*9YC4As7b#U@x6MC1gvC8!_+yM4ASP6oANC zAd<+}pyeOu6}|!we!VclV`+s4BS*SlL7CMKzq`+@jAgm;Z{%<-6;5^GpDimmLCJs9 z{Qo@Zv-iN%W|q^zY((7eYfCqj4)SoJ<#FMlcSq0nL1lwkOy?Fq0(vM4P<5B1XakAQkp z)KMDI-sQT>`bXi~M0`SC)vi^f>{F~w-YFCW$;)TL4%1rz=Lr!qvN#5yJz+KkuZVC;GU zS&I2S`rkk5{ZYMbg{s%RJ+ztqzoYBxDC+71UXQ+Lg9}5EKS7q{%aOmLw|paVEOG=} zhkuJjVs#KO3I>{(TFfKui=tzt;6}3|S$revVor69sjltJYdiqcHc4&hAlK~(zj(gcX_m147qgBMhA@xK&g@K zyp1ifX&xVTYtr457MwBtpeh4HU1{muRS+#_fd43|5~)Se(^OJdo{g~Te5c)lL8AoT zg~wy%XkE1Z18NINZ~QR}=>5xQ0mf1EWPbDOLrZ!lGf76g&h2T#__|`l(tzz?6xQ?@ z1f8a#*bj5qWu;M+eciZGV^twX53kBajtsj`rs^FsvNB|UY*_0@kFR?GLsj;U3OK7` zKNc!`-zh#nzG^W#nf;ey^KE#3_w`?a zZMTH+3a_Zyuq`?mn_5H#&wJ~3j_4WoLq_e87-_c&Q3+i+U^qWBkO&DmiCi8k;{7AY zx`B>$+t(OFJ$|HN{Alu&K|BpEzhdHMTx>TlO5=cD4L4|xwqWt+I*4D;KN6e!1^olP zqQqP#-uoLQ~~QE&Dm+)+XoXJyuh4-N!;_shmzhA$Zjvk5=f0bttPS^{Uv%z_{^nTS6sS_x%T=? z`+7+=xG&b%xhqXoUL^|%TiU9;_?EJZC3Z^TLA(%rxjmfP2=^>52$IKtz>r@!HJ}w-XCTvm3>}i?2A>~dQDBs}(ZH1)a{5Bw7{GgeIqfho%A4@t zQ3sbEraxr=l{wY0d$_NkMJwdH7nXT!v-a=Cl9G&OsJ!0v^4gF{Ni?h zw%LkzK$yYd)YWjP>h!q6J%tAo>UH28oXez#jk>ViU;2LV10#!0k;~b9!gJ80mSnBY zDYnuDl8zt>z&+VnmORjY3+pRi(kL{FH<7?)nCu)fa<?goksR&<5JOZ3FG+Lg|WCyo70uk+l{MVp$vTA9B8qwS-~@#M)*e(t#QIyd>P@ z%p#TGPmrP0kUiPHlZ}kkFmd!OWTmV_cr#R`q@hawd}D`7eBr_8xR6un3FW;`zD)4A zMi+`~vJtq8X{_WMjM?T)The|g@W7(nUNu|57hWTYL39GC=my4KqFhPt7 z@&3k~s9Z6F>_6sspfX6$2H%w|QrXerjckXvttxA@@HS=$4DrHg)cd+09Y4k*l`*IH zs-(Xf>kD0)q|!b{7hP~etZ$)iIMVH7y+DCU@%|t#TMKVpqIN*6)_pds37vvmGK;B~ z`K;!x{sRnIcz(g0)^x=Rn&S(8QDV?xU5I$U&~61fR8hWv_ngiN`GTaB$eP}sG82` zJSnG9n7|&<5n!zfxsGjR)S{zH_s9ODmmWGMG9Y6I3Iye+${Xv(Vv>!fP19ri%fYuX z#;aKB%yjyYnfJkoqvy}aIX#BP%MnSC~D!p>_1^V5yB{bEUN+{dJBgIzGebyFn^1X5ZhpTQ37};(il@P}xm- z$l)};;%zrFNG|w`=mMSHj&AbMBNb)QNs&*;)f+n_HbR)+(K1>T7Dnc{WLq;-Qqr4`^%PJB)#rbXNPg=LsEIQL9WI=gW6-L52wBc3jD&UefVc)N8Sy3$<}LT&;;euE+XU2 z92$h?Q-~uOXWD$#=`qZ)vuF%?@{}|KNdmE~G>{3W9)l^rLCTJvov;xy!k7>sW5NjR zGjJOY`wR=s5~EzPuC>_bfKR&E3-eeOV`h{`LC&$h2TYud0_tI6`!cg=ZDNrDj*WJb zMgQ!Esy1eSJ)uri!n^JzNHla)5<*dwgU_-rkWB?g*XeZEhh5awAR9f&%wViaae}Vm zvfHu#O_(R%!$3$T#Os@ofoR&p+)m)Og1%wXdzeI2GE{$PE)?4^@bk9pi#F2d| zV=aCS6@Oj_qO@Y!Y=8)p0egyB%_4=sZ+A46MKhp^W+0X6iRI8lr_EG(UHYDZ$BfQHmC*$?gIVp%HdNs|dd^3y z-pZmyA9D)F4*IW-e4?kpnw&QL!WDG^%7mh2z4NLU$gTiuq3jA=2PN8DlWuR=$gG@i zlrxatbo>dYh7-9}XYB%HA}5-3n9W!3%qsDnW{ROIjow9Rse!~ogW)@AKQaxRqKir*@@CdOWA#B z4+J0~X;=X1W&!tgp&OE7&X196)!e&c?l^jQSrB1Yn>VL(i?D+;ov(Kj`gm5GpJSw~<(!Ar-1;8}GU#~tf8fFPn$ zZC;;-od~zTS9wDx%}zERc!`RU56KRw$#kgVv&8-cljIB%*E=Y9anK!nTlaN}G-jQH zv>ZJ@hRdP(ugja6Dvdhi9AOrLlk9gvo)V#SM@Yf$PDu{64CoR?#VbMr1JU#Y>}w7) zRl1O;=t7S7??d`K)W(qgd0jly@wm+Uv1~*2hrzzk+$2>P4nuY5jvh)}iR_^n*1Be~ zuA7uAhLSGM1%lyKW$n;f9BeSBsEMBS{*WFHoM(U%0)HL*PdlTZ3lW0`6Z z=;-+f2cOknTyJKS?$aGi@JHY&Md0d+7J9_!H!x=dqZy1Kj+XzbOw97P5e`@zjbd^~ zL*y*~Gw94Hr!z-)D?*H=s_1NwW-uubgZ0-#dr?<%SgcZ)uvrM!O8P_H!C^^ebR2C< zu}X;LNS(@ctgq+RFKg7WV&4R}QtVRRyw2;~gw26vD6hJZS8X>0*Ru3uDrMsm>!-hX28LnC#tsPs@fK-YOCv9hE;9LRkbZv)iy^}+YDW8$(iwYt1Tx!JI%^8 zT~8x>Fx;s6t7~gwSmy)ddd^SwKTOgY zsP~}tf*&%)vgqmG^$}zWZ$7ZkzLVZHZrJp96}R| zjn$DGD+Rkz4H7djJ=b%a!I(sj1TW;e-Pn;3Bk#TF;14)@_+-4w%d$R*jvsQ2qW9%v zXL9EGYolCMpJ#QeNld7t=N)F6RVf#S?Dq_t8e=C$W&vvY+Ho<6)UlHal^rlo=MnJG z^B|cY<8iHo{dmr5?9X#Q{u6A=ywCl3H5+&t`{PK1@ha+w2ShRPc#0DbY}0yau3X{r zVjXUl><>9##d&cu*wNLonC{*D)_jxe70fg^hYKFi^{&?AnT}Ga<_3jsxTm5D$h>jy zfnrWDBYPvCsP0;=Cx+%BZ)nO<6dyM$Ks5Lsm+R8``jBPr0)51!CX+ZAtTr+jJOuOc zU(F)oGsz}T-6f*QjEm~ugV@z!af5nTiy1HIH{#mj6xbkt%KL-Fx`T7_+5OenRzw)6B!U!b{yZiBQ7H6eUJ^>~6S*p#MYEfv_d`Hg} z$Rk-4stF6@I4$P$Kj3x(ovK51HhUhZ;I-Cvo{zA|;2P@_Igw!5(m)+YsIoL_ zpS9t9LfooOSGU;Ef&s&&Pb9KPr~g+UAjy&bH}U>A)|k%_)GSc1ANqd|1H{ATwpF(_ zFKJk@Vyc^LI(U9dz0jqV?)v8C4f*-`wtV-rRSm6+uW4}CH(Z@>t6scf1tpc^(JuTK zPR=iFu+6>d+I&T#q25iqlKi3u-0Q&WUW)xk8;Xab!AG`UdXeAT7ffAO@Mh1AGtd8j zk#E@bRpzArG6je84L_6zxi8>p#j-{9kai&Ezn|k9u1larQgp{}0)BLl(L#NT;I0Ja zY<;xjSAZXli>SdzcQMc9+*QU@wzGTmr;~TET!Sn`X#%TEC(I4}L@x`ia2)({@ZMK)Kz+ji4gl_Ol zH2-J#h8ZqD<`MaP85b+hsLzI;W{fBGiQkF%a9wcV#LsfiY$gp$k7U{C#?t3Q?Z(dv ze=^j$_*wQ-p)N?UXP%WL=x0OiPtebSx)MLjKQ~fY_LiQzY}E<+B~aHU=o_J4h@TZ7 z@(C}(&+>l*)b$Da4yftJvhRYrDM4>Q-GZM*Z#~p)3HEnF-JYPo7wXjs`um|KO*?+f z{~rO@Cg^_x^#=Sb`jqdnDZ&0(sJA5OIq$kJLBAJjhGEhFHPjE_XVD{<+an43DAZ5l zXSsh1>TL=7x1rvipnnhQ-S}DbK7@LIg8ipZbG>ZQ;~O@833?8s4AZjDfc`M_7QL@P zeJit}1C-`UX$R_mJw7(mAKWIx_mDJUY_rrWV;?}#2x>5(V+PnPCC30 zHhA5#!hG)(Vo|=g1g@w@CJ>7y5yg^-;vzEtFH@6`&)>3#)ruv!LZBS2Sc2OEqFUT! znL$-Z63U&Z;7(MFo0_k>R$DJ_YHeJ>y7dTt|G=#%q{s&+(24F57 zlKt|20_;D5p6<99rah;@v>yv3-EzSj1bKW#^VbANp{`M%C1}Y>yjk?S1g-lCpNO6V zD8o$^bO0ItEyQW)2Z_@mkAU`|{|5Cl;2vt~&%rOb0&h2p{wl#HLF+w)cG2G|_#MGs z!AAvm2)-itf#85(YN`&`A$XqPbir!D#e&v52+Kv^CKwdFPw)qVy95skz9IOwU@H0m zrhBa5R|WG0rwEn{&Jes%aIWCxg4YUm2tFgYT`($`f^LuDT5=B06@38_p>=#VJ+7kowVUBQn9PsR91x|0OIE*KEJSMa|D zcL*L9d|U8+!4Vi+N$+cd69p+-n&wvst`K}t@POd^f=L+1>E0ojC3u#gUvReIHw3>U z_&ver1z#3?T`(s2zF-cj6!9NkvM*b}LDUj{Uj)fT8*C{~KuMoUU@D9NT1$PSW7yJ**Tj+0z;H`p> z32rB%?Yv1u_cTz96_?@J+!F1V?3Q|6>K+g69fO75t{) zHG<0oR|tMbaHrr)g6|1_ESNt=hvyZ%Kyaquje^~Rrr=$Iy@LNO_=Mmyf;$Amf-eca zD)@WBV}hRwjyz4rYmA^va265yUnTk)(Jv5e67%Z?R{>c*okWz+1~Gp~aF<|OwhqrF zc(!1X;5P)X7Hkq+E%+@#GPAS%pA&pRaG&4-!NYX@)0>Mhbd4iV-HVL*0wh0CWZxaj&-Y&RV@cV-QE%=P!4#9nb5y9UJek%ACmyYlG zf)@*3F4!P=onVJxx8R+EKNj36cueqbf~h$=oY8`(2%aT)zThmuuM5r>Tr9X$aFt-Y z;CjKWf1f0KEXc0LxOJ! z{zWk3t2&%h1<&NV4Dq1Meyo_A&!cE?e1(MtC8eb$rIQN3;J$5X0i=oZ`^R#`x1b*I z^Q!;P%Yjob>83yZ(F>29|77T$C+;&gb|qm&{KWCM&d0$KJmI)c{nLL;J%RhoHly#( z=N@}yOPNSXdeK<38lH@eu4HVQz1R5rwNJnQ`c3D@Hnz}oa~uC3ZO4CXV;WpU_8M!l zfyQN(PgXv>?XG8@dG_^4Y~uzvi0lck*#zVlUb981(*5Bz_r=X};qeOS!fWowKPKuR zdK{|AzSu?^iN6@z$oB{$FNW8+ffy>_)&mv4@U&d!M|fJEh63*Fgs1V*Mq6y2-?+ZY zm{)7et9$zU|M_6abH8gpSgvKDM!0kaP2;i>V_LN_ZJ}{li!ra=*t{CXc(r-+THuq8 zn~wjy@St&hnQ?uL| z#%Ase8k^nte`f2JurH$7JogzJ)%o9}-1vCbk&q)J20wJ^bIuy+mUpcMy$@CHQ~tX6H|4$2K2Bz>&S-HOGPc!fXDj(2KOI$SX5D zJYf4BW|>MwcTT7^3CQXRTk+|90N_F@G5xMuU6*O&kGNAJCI@m1CF^SCjW{_&oNQ(h^v`CZrH6y{9S|}-C3W__6NjJ$pT{D*3H?khNjTXG=oU z{i@)2!Se($Jy7;%BQccKnkzU38AmkjtHZa_#4S(s!A-k4-I+2yGgM^*lTl{r zMcIyZrKs$%sW)#bnQ&9)Y&>F z&Gy}#9!_mTaQwolwORo-m29Xwz7~HjuOw{0op$=|J_??1@>QlA>Lowi>u2uFw)eW> z!Z$n5v3{d+N-bix$h3dEm-Iqq-S}tFji%k#>w?->Q4X&9iy0w(K^PC)w|hzk?Dy&? z1*Z+D*cn>BfRb|QtNKq{@MU@6p4WPD@p^*&PM?Z=`v`w86M?(?ZU%+q`zrIa%n2qr z*0~8)HF8AXYUOS60~t*IeDH07Yb(<3S#>p-dR9G=el_lU1p3eh;2bhe4x*v}S0S_( zeTOuxE_>2m<^J?co&4z~9k`;2MC%CPDn2F0+HWmA-kv^QC1yZ*v|@;o^IcRDe9=_5 zRBQAc3U6m3Hl3d)8GVj*8 zN53A?$X1L*S8M5iyg0&}=@!2clG$WVQ!MH%9At|vI8NSXM0LfxwlL8WCjCft6Qp;j zQVbr14#iz!&doHh%p1RZ!j<;YzV-}rfp`4g>9DIc7U2F&9)06eHE9;vBs^5Sy0 z7KH%LNzf@NEn9QThyg`o26%Jn9}kA$iI|94PQuI(qwIDqYY^OrXCs2O19n{Lp>54U zyNA4Ej3K%BxG8EYRWJ75GD5%HYpRrhwi{L~dfzut!6soU#8zRhy$?CbmoLx3elYl; zlwW3op#qSb$6598oOq!&7kYkXTgikrb*o@@Y|RFcTA=HKu9UtBxG}Nk`7iimlFjP83Dx%L zAg10X#zQBtn2);b0oN8jBrUS%fRgv9sxCNgou2uP6Ja%2d9_r7ILjPmEm&1}D=V3* zo44JM)CSW_QyC}6x;hNb^BONAoona>!ZEafhlOz6CU@u5eQZOO1o~2zBm_K5BhKrn zlm=YKs%h$~X=af8jyEY;q`EZyG{^dfk>8+>?vWM6w$+V4zoMaP#`L`4lTeg}lMy|1 zo{Vp)BGUd9#@oDC)fU|Rm`g&#qHv{|MS5_!$aLL_oURVrH^TsZr80NjNpaJ75yW(! z4yZB!i8j~?f^nr$cDin6vyF1)4{tO3Zq5sCRYlb1)~3ETf5#GOj_kf%PfLI*=Gvp{ zX$FYl&`ckTSXCM6XG(y$Qeu{E*zrd^c3iFlb(Lx>h^&nVI^Q3>8{V5Rh;?trwRg-E z%(1+=)`Udy3#TqpNL9R3I!9hR#;ugF{Vv*@YIvHB2sZgj^;i`=K%KsD9ryVS8NbL_ z?AlnurfbQK~I)s5G}P**h!+q!-&1X<~Akyq^^zUQ(e)4@BNdyJd_{3IlE##S0g zT0zCI->c-L=+|`?hFnSJ=%ftgCViwaTG=r({pKiKYE`j%)+|@{kVIsFlU!xBV#1H- z$kL%XBEl~4p!tQRzwRj4QhUtw=MZ7PiPwA~8CQ?I&Yl7Loqsojo*$Y)tgfFMUdDrN zlj%s&4*)}!uM9Fe(KCEkf-74kdym)}BITcO(B)|Bl%O z>R0y*$8X4* z{!5RmitJeb0W?E-v2}{T1#hO`6Tbm031+E+VbEkqjmW zGZ%tX7Uy$_o*%C%>zoQ9r`SEBi@43m@X*~;1g3};^BLvdH&@3y$konXXn z(-Ml%D{ZAqwo#uNPaQob^au5r`tbJHZJbi{?WsPr2eTwC!X0xY+=L2T4Kiin5v+sy z9(laOsnQ9w9v1?`yIGY50pVHp_EX?#q3Igqs~dy1sb+(EBvoWoE=*IA!R;~CD?E<& zP}Vs$DUgS0ZsQ&X2I*cRUkTR)Lj8$u9adJ}<*x{Rex5$zx_{*c6!9Rf{oTYH}Zx%CZJN^%c#VSZsuT)LN zUU>8u@K+M9(2Lc6CE-O49sO@ns19gCjz?mo96e{KYD;pVbUpFKtrFAa@YOl&m|iop z@=o?Ooov756ali4JWf}>Hon;L+`>PjqrQgU?zv0 zA-F@wnZ>D0;{;dc43+Koau?aLE*JihVE8#z(aWa3d=Y#s_y;q&1&#aQ>I-Lb@!_#> z&y!%^@ngZ|#&XzWDmgJ+@o?@7^rC8BJMMrImV=U4v&03BNB$n|_$;yiEL?UN6sgl6 z#07_NY8Cu41NtxJeFrr;HPt#03w4UMEMVvdA)Wx!QwXH#+Y_zFMfogxL+G&MZ918P z@9o=z3tD^oFx|&YTHWDRts+%VTw_^&m^->s5uP?Nl`I;IijnR?Dz%U{_+vnQyJgak z;;0QdH(?R@aB|WPL-{izj)zB$=e-j|ueS}f=bNL{szp;Vrv|F@^xP6GR&GSJU^(>si{QvmGk-14 zM=vMz5CkjMpxTtOO@p7`MV+AQ}CY+Esw(~RpIN2Zjr7Of9a8txl$MoPIXwK%z(92)bb97$&06D42dyrgf|45O58*nT zZO+PNS2eV{o3F-gndK`QvopB40`3(pi(BEA zVy)dx4a=_yG`gqqZq8Lr4a?k(i&wapHw!s9S-EUEFW}gwEnnPp;|g5babLf3aeeFJ zz|tjd@TE2^2`pXJkPwfh%j+9j8t}I~;J&J<`MMQWJmSGGU5oWKJnYC5ZE~Z<2*ecyUT`T#2*}v}{xfOv{Fen$<@`s!}3~EaL_s0+?I)hjMekkix zi(qJmpF!l&0Biqr0P7wm+3GA{oai}{^4pX^i+Z}_HvvC(Pl@ijXdxf%_*t{Q z*zsB)mHeswYoO)sJ|`ZwwHyK6_|e^5LF}Ze??t$?!lD7=$6pQvL4O(4mH1iy zuY{U@EPVsi)d~9Rpsr2OuY`JGg1!T4)-lV!0rjE;{RXJ(6ZCgN-I$=i2kNE-{r916 zNzgw8bs$0iQ>fb#^iM5Ey_Vo1 z6YAJ7y>$SEizthiEyYEYW%amqQfONi0Pr3NuYvFu2rgpa0?JLefU<0H+mhwDgwnKh zMPNBzVj#Bg7E04%-a(P47~lkVP?jy@C6wh*^CHJ`jvu&%g26<+)G&n)HZ(1T8&F$P z&+8~n@Q3>-bcpLH%j=;lvN1}ykAiz8ypf_}CRbYYr4(F7nWFAu@GR{rs+P61E)T@7 zeIU)h#V;8ZnfIi~D@EP`Vv!)(3aFnYI7jeG!DWIs3w~ShyMjLwwC-f=5j~INN%yyc zQ9&Nb)BIz>B=j-Vlc9z9HNir`IYczxdeL7ic$1(Zc()+swUf?+f=>xHjXl`viX=_>kbw1dj-QCU{D! z_J5k-S%Omq=LudRc&*?qg4UZBKcwDcvppu}JBi5eu;43V{yLEP{}vJXZ{0olOzcNt zGnM`vf~N!N-a~}@b7_va7YJS;c#+@&!OI125$qJ)BKSSQoq{h3{y}g+a16Er7+#K` z^(MyoqQ6wIMbH%dj-Ykt zcavZjkomWsm}|5Bh~}WjV+-Qbg4+dO6g(t&MDRnw&jg((Y5#7)^90KUs|CL)xLEKS z!8L;45xigU3Bg|oT6b9bME^&@zX-Z9abP;e2^I-f2=bjL+SdzSE7&U7CKwd#5##|D z{e55X3BhLs!-9Q+zZZN*@B_iW3i2IW(mP4;Y(eXe%;lo57ra*RCc$-r-xGXJFf6!V z@VA0d!M6lI5d5oPTDp$UX@WU|69fwd%LJzj&JnB?yi)KQ!J7nE3z~wr3*IfrHwT#? z4+=gaxJ_`U;C{h~;M;=l6H(7U5=_EGmi0WHn2R|Ako2>OaF-+aHQK|Smk4)dG>5wy z!EV8gg1ZHOBY1=edc5mHI%DOo&N+e?3SK7IBKTi|4-5W6@IArL1SjGYpYgd`@Oq*L zb1%`aBO?5bf?LFVE0FQ|2@&bC?))4O`y)j7dq?oNnEwq(f1@yoqCcL@GklNWB*9X_ zZwg)~cq8$v*bEWi!P79&XLx4{juR{uoF%wG@Cw0t!D|Iu1Xl^( zCiq>!gG9tr-6cYJyhFrrldz~FjuvzYP7s_USSPqd@H)Yp1iJ;-3EnRF--53TzA5;Q z;0VlT8U87PZo%`2XQQ4HQEpR#ET@@7lv6tD3sG&aw0@q?YSNSw^F$XHPx{h)R%_8$ z@Z-9NtEJIuwWBoZPs{Xd0$0>(=)nfnMd)!s(+G zM1RUln!*Z(DD9^^%>ouJ!r?AN6(bIAMB0T&XUEh#%E9_XnY3F;pNG4UAEci4nb#;Z*=g1gop>g(vaW% zPSC60Xi={4q?5(kL%m<0rGcZzH!>Jaj34K2`U|IW?WwY&359jJt@~hb!iKFhv}Ev8 zq`ULv&QFpYJrq~x@1-TSa2J8fl^|rAIhvIB(q8AdoQJftTuy@=)Gf5)lUZeB^d2*61PUXw^v}k` zde|A|Xo|LuwqY_Di)jj{elzb8V`7yik~?7ki9Sd$dCI9`g&kzWwcgZD%6Sz0L1}TAhO!QB(Gj*P0JGZxdBxl$=0V%V5KYHjgdxeTH%}$o4_AO@ zF>N&squ391$fYYAj+Z*i#vW4J|h&z6&yElHnZ7SqsItTI9+xua6c zc-Dulh`L#>!U;gcs54>&KDHw>tIfQ7jJ)Uc0~s?kOPo)iD~evHnuy2!(c<5Ga*)}rlX~rg2Teh8)dvZ{xivw;z|UpkH4T$ zJ)4<19rajosYyLvrh5T1Lsdcare+=Fc%k1gRCUE;&AQ%NFG;IIDhk$J7)qaFo;zW@ zZ(<&Z-;$|c5izGu0FMq$OjSK*CDxVT=B;cP;MV9mihhILA$xxBNJG8WgNk2k<|UQB zYfQ|BGefoVj-`=zDKn8A47%ql`?gV@34805na?qKGtmYr^aDmb+BEvcA2TO1{iVOu zXXzc8s9ET?GE-F6T@+k3&8H5Ub$=SX2i$wArb)e2^`~R`WvDi0yx>?*ZkojLK({^w49=j3RVScCjW)uhj8d+*N8Uh@IOFdz zInhPOPn@Ncf4-V zNDKLB$B!c$bH0cgesIUG$NFf;-vxq}xl7g=mY#0-&Bf1BQ%`qTHvNChy$zh6MRoVT zN$$b|H*Ay@1Fm{k7aN*|23RypV%@w)+&~}+q&$hn0vc$95RyufykHXH^2(iH&7)}3 z8vgLu^l#cmo7QO4=Sg@=coBktB)W@HY5$3$M3EOOn&+AA80PDNXJ zp2iw^CougIz7$TdKK|A0fvFy84@}P~Jd9`2T7P=~R-o#e-oJzA*1GU%JS$In|4yFO zA1VCDJXh+%lXz~g3!lUD@VfB1JWE)l{L^_>pQo?};3)o5{VwCVo4@q_&v>3t7hcTs zl)A9?xO(cspWt~Ke+i#7Q}t`Yw~l9(nZkd?^W3`dZ9HFE7v{0}y^=kuFGXsNG3`11 zOOe~@{=fT$(_;LRCdm`_oEF%=P}7xv{y}zqnignph}|A@Bi3o~47Q&ZTKJs?&tMzs z^3&wOtc$HFww@MUwTQg(fOh$xU$w|wpxKweEuP({PTOg^%=V#T6Kaw6qRf|>wx4W2 zs>@xMxj!^EmE6~t9n4r*Y$g@EOHKFFF4-g=3;4Z&r@`Qg9~N#-zd>0nZ3{Uce6oyewey1GYB88w37hz<&$)Sit84 z9>E}2Ipu(F3;0I?#{`@h@PdFJ2zYhCr2#(?up01-0XGG_E8u+rcLz*+L`DPZbChVo zUrWF@1bkb-j)0Q`_TMX-6Y-Y?Tomy7fGY!jI^bUgyfxrg0&WZVc)%wDJ{j=G0iO-{ z%Yf;7=*f@S+nIaRo{@q~PVbEHm_;&&27ftj?dsJVK z@Erjk2>8u_djh7ts&^rnmH*s;7YCdh@S_1&1pHJ$`<^@bHbr=A!0iE_4EV!;z(L4;;W;wku>nsE_>O>S z&uMIgCkLDwF!@otF2XkiyfNU~fSUte0^bge%Y-L&)%@^|YQGY+SMZ65SRiB2I` z_%c)W2EDfLJ@aj|`-iw?_T6g5d8Y>nmDSBO*ur$=M-x0qK)&lu$KU*)}h2&5xbJ^N3?rc`T2^0ert(Db;PGuaVKa)Ux(Ca^$BP z;&%&K*RNXE{-+Z4P{YIGCoGuvi9~UIv>(?NA_^b8cqCNbdc->H}U_Jr~NCqr+n8<(ACn}Qx-3T z0?l29cFBief{xMUe_TALI#r*6Hvd$g(6RK4&}UTW{!Z5O|mjqCS);JC)i`1Iwt zE;5+~%{yvh_5Fvs`g{PecJ_K*ct~Fq(TZVNhu><*k5x%#4(R!3zX|O5yOn>B-#L4f zXCDFwF4rgatOX2((dQ3uS$z>Pw`w$W4>B9mZF)X1T4pK8uc6XGgbZFwIcu%HZs04U z#78SFYacg*fiaVDCS!2zor=RopO?ORTQ@m*ZkPR#%W=*}GLe;zB)WOkp@I1bLg$l* zcHQB8v``4`j&SzEDUY49tLyHTRqt0^!6|%So^aPM{2;mCCR}!wY>|B2w1Gb+RGYfE zo8GeO&14v-uW!cHq3qNObzS-(<`A*RffH$a_FQ7u^P$&)NBNhZs(zoD?8Q85bam8! z2yhPar^9b^=f_H>oS&bi_1A^-D*UhA`Q|&0ei4X|^-<6Ed`bI7^GFd%vW|AUPMgoH z=w2dwBdV8vA;rf#e?Z4k)z&ZQD|?GZby=cC$7XLf4jFu#^6;r73xUfaiC1p zvVTk839KRi(RY1Ug4az4-pG}h?4tGqe}^^Hb07E{9XWr=-}J?twbtx-jn84THabt?fQ_hp~URb|C4b>8DQ6ufH9r zLtViTLd~#AN295kzmp@(>|wuMb+{Cvbo!0pPwDH^_2@(1gdPl_dCEJ;X2JOW_3T<9{1_k?NtJ>LGiO+N$Ri=IFNdR|>z4 zaIk=-e+OaJKfV7$o;8e9xWD~K{gm3R^4>+bQkPyLsJ$*ck>}xc;r{j`*>c1ysXXcT5{o>CX)vG~0b`%jUW2l>s(BSK?M_Mp$y zB@i9|reC;F;4g7Y5C$Q$^P|IDUqt|5d|`D+NBWe1GiA3m|+(H=99{Jr~XVgP&33DjHb9Px+X znE}TJyddEF1O8b+yQ4t*PexeuP=4{gpfws@yAShk3FTE$i?+rLT z;GBRT4tRCIPXtVMr~et@F9g)L3xq$}pY}%hhXFOF^m zXFB4aj`&|Gp86b#+!3_1(ZIJwIGu@>BMQAwe){{LjlMYEe<)x&8;xXGynv0XWN3If zJHzQ`j(o*-h8GxH`bn;9HaNP8$+qt2c7|q_o^AQ0ihX~(f}%Ox&mJjrZI`-b%@+yx zJ7e<(A*pXtk=nE^pUgXTw(u%&Gsp?qX;l2(v zyt&%TYA54fs<&tK`>_Hj?b5y#cQxzm$epi+F8ivz7Gl=5>cevO>*oLe2%b=c=1u+j z>#DP9%U0smrAn@*>G|XcBXaDwz7Cfnluo}9{3(5XI_W;?m(of9s7KKsUwYR)K)P3= zTmAzG-kS=o!y&wg_u_XG72Qlox}@}T)lanPuUn4d#oLHazf`{zPOv`yx6v&VtyB-` zda8?_Q&@VU=$pbk7QcaXE5x1s)c5XlFbSPY(1J#?<8`_|$rFkS;)vAJUnS4l1C9$g zH6Xk6_WrtnS-`&x_*Vfp29&)~_`VwOu7D2){C2>95BRfy^0J_Oa-Ayp`vKD(tML(@ z8jy1WANt@Wi>~f3PtV}w?dc;WJNeI|lmGAR?5tEqoz=w~{a)T~+Y?Ne`Z5%aeZ*Ey5@`iLYQ|#yU+NB_392YrjEW+gH&Iy05fR5r+@^NKP z)lD)yo8Vc;Uhy5tou$9AN0+WWa`W^li#W^v^O?_`rGKiWs9Bj6*RtkH3EV}Lpc$lA z-KD48YI!)g=00@Hor;w)PAwjNKEhThmOc(iD)}{)Mt2-vrOmgBaY;NpZ@WQ_7|o|y zm8E5^v`(nmj(dij$coY}ES;PE^pw3E$I0wK&pCcxt!2&0%z8Sz1ot#8d;6^d6giTQ zpH^oL!ch*Wr*%Ek*LI&LS=tBYDSpmoTD9j3FP=|=p%={4h;v)bSrr~{ZRa00o34AZ zXR@<|)MmR=9e?YM&}3TP^DR#Ge2d4CS?fJn&poB;f(MN*{ONkS1EbSiZP!*w4{Q?vFqXNTiF{_?6TKYFTgPN*%IyG{fa}^{~#tuT<~R` zpSra|qS1EDcG;hpD!*XcF7v!y; z)HpGSbx$`{sEi(8F>_?gn)kZJu97e4*Pow5#)e%}7UtG}^4{NxnNHkY%=nejC$_9r zS5;e$d!Zfv8&43Sx=OEGHkRUM=jG%1s;hEQv%GZts(W>#rD^F9dF-*x51q077c0?{ z=@4k=r@V}WS0|gwLqU(~pxpVnt$b4WjYQ1N%O{NPIia-V=-Tc@fp%plXshK^x6W$o zarxleDng)|wjJlkG~H#ATV}J9M5BEAuo2VCUFO`XrTV`S0nTEh->e?ZoIC$GH%`jS zU)_lf(+J}_2g=b|5+oTsVG0ngITaplM=&#sT6%{DNq%uFhf>#EpaSIB(MC*_P9B*# z?kRX1dvMug*In|~FBDynijKOMzhJD~?FHRt9AwBSWp2Lc^QCjU4lex~WptyY$;qIm zrIs~c;(t0Ld#s|Wr7HhL9(Eq^;#lzjv^oN7zqj5Rx$OP@?dab2&d+9NsT-@D@XUv; z`p)9tZ*Y}mgB@ke>zQ;p8z-3|SPIEh5r*}IyzQn{xbv{8uAME><^HzZ2!HjVLQZtZ zuI%NPKda8r&&Rgq=&q9ZpiyP%&FCB5p zZp5PZ@qzD2fOtc-nbvs=VVwm*`GK=^w9p0vmF&#yd}!ABc{MFRXV{2y%3an$ zE!Ag4Ek~t;%%#t*+HRKemNk>H@vDDr6F}D%5Dee|@_)Pvf z-{N~J({%-7Vy**(AI4k72&qkL{|G`Km<{!Odm($oJLXPxjBiK0U;8B9M`#%I4T%pO z_yGUYczv_#ec;1_4>?M*GndVV@l1h9(P;pU{>}2kg=&cWl+v16QLR+J}c8M z3ozS{L%Csl(85diSXYfRbwLS4?WG!Tw_0*ejpl71hgickH5tB1Ahf+r3!yPcWjb97 zL(1>pOz$s0+*6)T+qT`5<2-V>>UIr!!ZW8lG9Ec#$8WPYk0QEd&FA>fN6z2S30(Ge zyR&1@dHJ(CF)Y1j44+AF+vQ1?evgRZeoTK_b;jBkFHoze&l9px6Rfy5cMu^xf%D;p z`n2LsgzYZorYejHRUw;kH&?0dE_JiPr_{LnwMLAE?<%8@^NTqxYu-lB84*s@?tUV| z(i#2M=SD87)rkh@lZjCnW-W9)i(qdnbUf>VZgtS;!M0t9Cq)sPYd&@5d@S8ju-qu3 zadV|wI*BE{k$LpA(vp#oF0;)sNX7WL3A`Oy=SkkA+)likAVBBvuJTJF939WvKIyw} zYWMj3h%Usa3R{|kqdQ;p@e(L2`IHK~T;{>nH}TcTmNj<*)PJ{5AxL_5x8=pLG8z}8 zLejE!4JqOt5aT&(T@&TwXbs1mjHzxzbPxaQ?*P16(KQ94gKG}iSrdq(mLt(pVuKtZ zK6=9IN_e6^wuhH8Xw10##eBluFZhLFtx0GpV-8joF-u--e5+6pFD@sdD~!3 zdSbSgwF?mz48*FR0eAjHK{g6!R#t{Mo_#ki&hBO=Ql_!ljAuEU@GR%?#p&LfuAgT1 za_P1x{{4gK2lc95IGGY+LfUHS%hpZZVzbd>E4EeKvSzHN0rl`~dV6F(y|n7N>Z`J7L+J#xw6$XK!sjn;QnY zS)i8Ti?!{mY9}AMC-SHxl6EXyU5@njX(Z!4r*SuFfq;@v1 zy0^Y*-=mnDsU^1`PO9C%!_vQH<@ ze`)?P?YWFAjsM{r{vAA4|4CDG^8VTCbF^26=|V>Viq@R!WXX?J%#QEjEAQB*tkja9 zrSK%r)Ag;)f=l;i(`nOO-i)5knJy(+Hp1ZN@y|^%VLFb{*OVjsw^OfV z&$X<22ff6tRxG5#hsRriOa@T9TodL7^C*be7=293+6@fcf#`GKMqZG)&VQS`Zj;No z%7UwK4|n-hR}R1Cl%`7MkBB?DQ&&O!KiTwq&wH=DhPxm0FRR#r?8-HlUA_3SD=)dM zgHr|z7s@}~l^=dB?5^RnEu9&txp3o4GWG9tzTkIaqy2qds)*mvfc+un%JMhuk4 z@Ln9R`xX(4 zi%>0{(lacJ-;7oSF%e~A-p-%epg!qu8-DTx_Xou*`=xSIIKle({|?*mFbY=PRd3mn zwWv}3Q@Fx2O)SDvJCrBAKb2?YNn!0zSL(uN^W0t+=CSwTndc}!gx3DDGC7hb^ggu3vb^E{<4yoBeTy6{S#r`3gJ*OmxP z^^tv5bxPq+^DJIX;ahl~TNmcB_zmf||E6;d^*{Mu`|F6fpI5Tg|7~3Y_1ort;jR6` zI|%P4?=@`tDE|Y5b%*L<7|(70$w1y{`=8J4n5*QJZNb9JKFZCQ%P+?>+lM&)VCNW4 z=Tw9po8UH!AEWT|6dZdvoh<|oM6ic&rmoF&f`y|Hj)ub!A0h5telo&P$RFD!^2T<# zuEJa)Pi$;GoQWeiys+t{1l7A_k)Gx)xMpF^-CA)&hKH*;e)f^YmWX2+3l@HaHZuHd ze_&?7%LAtUi9Es^0{%n5{}XU`!0!coI-s0E45D*e0=_-q=>f+DJU`&20skUk^6B=e z2&Z!qUyN`%7x7?(p9uH^;NW&v;}QNzz+VPD0-2k+cT+y6e#yCXiGhxk~8)4iQ_5xzCx z*8)BgurFXb?{Fk#s2o{71&)X;aw4acfg4OFAVsBfb#-g6>xFDj|EKU9&U~B zKL*?$@ZNwA2iy~|FW?UX9t!w+Hg;6+cLY2u;OKxC1pFTXuMYUpfXf4ZB49P(rvv^~ z!2dVkzXaSCP&+j$|C<5R{hj?0ekR~xz#+(Dm3MT&p#k3%aCpGe1D+kQ zJK%c*P7gRY;DUhZp3hARLx;5i{|YEN=)RBWaEIclN4nSZdnhmpzdqpG0-hOgY`~cT zF9~=}z~npb)(C$k;MRcm1pH>e0|B26_i)^JU!rf0WS)ee99#s za(@}|w*}l1@UDQn1MUm>vw+Pg(5lA?0sk=I$bjz-I6mOCfFB5WZNQ}gKNaxyfSUvU zTfqARem~%I0f(TZsUF7%Y!7%wz)=Cm2AmpjZoowWlMlER5l%kfJ{#e`514$tJsjb0 z2izC%rvaPTH&DHf2zXq;69S$bup{88fD;4G4fvse9}oD&fOiB;zTTdU@Q(uiG~n|A zUw@p}rxNhgfMWw*81RDu7Y4jG;3oq9Wx&4+_|F0F4tO6>e7QTq-wOD>fXR1U3u8|7 zd1JtL1Ux(72LoOk@Z$l^haCAnAK||bxHaJRfcFG^IAHQAcOb$~2TVTYBr{c?qXc>P z`UsyG;kQOupS2rQ!KY`$zY{2V@g70s#YDw}XIj8N4Y)9%`JUtb4G~@)@P7vUV!(e1 zxIJKRz#jxmzUYo(J*M(n0uBp^KKPLjU6oFAaBd^MJADRcHwHS-@ve8h^6yS>meR;i z>kF+)20G6X-?CiYzMdrcU$hSSi=ov`?aK+^VQk*cu@#o>IQ^UWDMKx9I{gsG1*U0V;6QeK_OTLI&!7lS&TdwokL$SW zs_iW|t@21|p?rF!W#tDH-r|W)!_Qey_LJ(lgYb{0?_Me^--TTE2h~Y~!K51Robd4% z0ZrN6cuTYQSCy;XgO=_i@2nM1m8H_tL-RXv-{$muXIJ+*EcxUiXvOuvMJ=A2%(XA(d2jeI|foGmqK)n_tWxj0{80 zq^xaV{4Y&4t(Psk@XXOH24=;7)GgO>iYNMPvJ1v)krR$J+*GERZh zg92|A5a&G@$0(TCVf zrr25IBbx}*_7B;CrMs(R{+`70lebTxb<{-avyR8CwJVxwb*4+Q{Vi)2Vw~fI5r*^G zu$CP5iE?8{&nd$X6S8mPzX(3q)_#|eZE4>wL^D3|Vs`h=2{*n-K)(HyWAs(!><%%- zBZmE5*6OZj6A`TUTh?~b3F3hD-u2}npn@4lLrLXOdrT$nInVr|V97Fe$LOT)SUFS~2GMLwwh8eftA?RpwMo%c{X>7bMaW$g&muk65(gD7!6e`Szp?1*Q_96>oxserSG zI3tc8wQPQN53!pZ<%DYa<2S=xN<>R77H0V@&#GUwbfbMJZFrnKacq2TCX$wJ95De| zJm?UWhad9SSNU?4W6MU3{^O>i15}O2-9@k?I)sr9{*BcHO^hBneb$N#J7t4&wEUA0i>FHXvuZ?%!F` z0nDbQPdXoXw^55qX*7Me<^u8R`u1jZA(-bCY>JYGbi7ZtT*7~ekA;5fg!$wuGI>D6`ZyNS3Uwco#) z`qc7&1!*B3XH}M+Se+z~Up<3{YdX*5Hz7(FueaneeE8LVyuQ5ex^k94l43UDh_;s*@#Vu(f@~5=5K`8>C zQ0yF6;lBiNKNZQ`GZ?*>jx#NVs;QlM+l^3b15Yc)+;ZspH&Ke(oG+#BjYw6B96)vBmlZY2jC#A%ZI951k(mUc#&31y*A*5!~^C?qMBSui^_W_k& z)?uaJ4xFCuA&;bq!Mf*@M=X3n6=n7!GFCu5ld87?r-9&LAP`i6g32_U_hN1h3FQ-1 zfe!#xpu$SO52#67Lw6eao+PY%orIN7g)5&Ls(cD7pTg-w!*j_mIUxz$a??bf)JL3P z3eTOh+pit5zJ0lJ_U9Hwf^`$1{_?gy#_dzwOdpsi1}m-3`N&nzUHi6+IIPff!MyEc zb4m9nR7s4Lsx)+(G`N}b)GSXii$*Ag@8`~{^09d5!moX-^&ci9{;%Eoz3W!KhiA>4dMo zf{ci8b9!eQwDii&!hhtd?Oz88=V*S)NxQ8K38@g`K-V5AQRzmX;!5KWG<*--LsAf3 z$_sj@dERm`c=vpOUKe3vOfnB>>X8nV#*&G!0&7UG|A#CTtLCh@r$lOftV4bt%dUh9 zCB4Kk$stVX*6M3Z`7qQ3{3pb$EKPz8=x$XGS#@P+qe+ZE&*tbmq_%baa_IpQ45#l6 z9n;o`wviL5@HUmzc1Bdn1QhxxN=1oglS6vlBBt!=Fqe%*`g{Hb;JKZQ8aLusO(KHl z)BCf;?5gEVatLa43tkY7RAPlSngtI}UmHXz-yRC9&-VghI$UtZ6sd#Qe%WCM!-|csi)%eKU($UmYX(nbi+mXq7dPH z$8N;x_T^wWzyF}@CK8g=N$q}P@xZmXA3%-CUPmV#xS8XK)8?H{rg`I))BTv&59e9b zRUH^C<_+C>1iH+j1INpq!xo?5!q0i>gb}6JbwdYZ;~Q*(tA1Ii|AeE{OSQZdg{zzn zKfjcpcuvmyrZyNH= zN5;Xtd|{cRSPLt>oCT4ZLR8%ILJ}1|0cJC9WTBa8e0eM|zklE%d`(QBH;IhdGuEB; z{g`#e$>DXzsyhc;51vmJ*Yb592zs~XZ^`!T*#Fi+cRu_}&fhkJ405;TuY;-Ds3#Xo z$|~TwTlH$i3xitL?pGQ+YF$NV<`B|QMSQfBo$0af^*aFXZCSIL7nVTWjjV-?-C_u7eFdl#R{2P}0dunRXWOWx!sj&)*KNq+RNb>|1G)47^rvHvHI zig&I(aFJH=rM3CcyqhzPtITo9lE25bk0rc4HyNT zOON3oI*ihqo%y3)yLvd~Hls-Ejo!)wr>TH{p)O5OZ#K)2A=w=}e)!fwyB~fbKDT~6 zMCI6Kg(R_@it~SM#2EcdmwdA&;H>8B{1!_7{!(^g_@nhZIPY8f(OZ=#9Yby7UW4YK z+gkY-*IVqszkeaK>%MEx>bh_7+w<1XbUngnb?vk>hcWG9$&Ys2Y*%@d|3?qSyS6n4 zK1_4+(q~3b_)KZZJ)8-%_u;ENJGb;d-hbzm+f;|V{0a9Yec*C(5OMhL+^bI02Q|5Z zd)dO`Ta@|?rrihQ-`OX3&A;^Ud?{w!;>+h>st;veMfQby;HNK_2`;+)BbSl?v@OcLZ^7nWZUM~L(ImoPFq4icQ;ESS{Mb1}L|ML>rX!QBTw?@xP-x>u~ z)4AuJd-22z&YNDK4OcPeO`CYZ*ctCV@7(l8@u!Xa(7@-*>JFXNeKfR5nwgZc*Vy0i z0Dfm`XUJZI&w!fmS;=13WcKUk|NY1Nv;IrC>DT|v*f2#5dHFMAWewN5pCplfBlweS z0fqgPZg@Nkq;w;BR{heMu?p#KQ$+kKKn1%4rgV35!)y+5>8CXMJ1<~5*HyuirFx{F zp7l4Izq(?YhKGGWrAzPT50Eb5R@#(KGiqw9;?D-(D>*Z^6`7=O^l82jDMc6c30t2H z_-;C>sYxc~^h@QYaDw&mzs;Gkghz0oGg*!Ak1TGrs@^&?#+H}0A%#UN(L04jX0H_#cXQStVZbfC^WjVn@n zz1~OoX5O6*VfB7SzxU#!^iw-7O97z5SM>|)j8XdO{Yw6JL!@5<)0r!6V%1Ju$tCgS z3psMNaN!3zbagoguCCy`)qHuNS;$!{MR&z@D&kJDBsOCkWC}ZJcFLx*j@xFg`Nm(^KJ3 z00;3-zL}KoONuAozY3D?*Mg*b7-R2Xc>M;f(Su);oA}MJ0t$_h#!5d zmp>M$^3M|_{R!-=iVp7*q`db6)sBkxu`Pv3k!;EsU11KRhsc>f;}{&B!x1pGaCQTdM!I5gl10n>N4-WB2Z z1e_UgPQaxBKM`o?Vq2^AZ>KNblqwl}-q}Nba zx#XHfuYof1R_dnt3HG&LH~+ou9+o`RPjdp|p!m%~=IEW`l%H<5IpyRCr+HWMs{W^R z`i9;&R1WfOy5>C&0wVc0%TjBJMp;y#R z@qfwRg?flzN+&22Tl#Gvuz>&~)9R)6COW0I64lgA0MStV622lL9_r)&J9LNC$KnCa zef6|4Uhu(pNo`8IWd2o`{F(LtU^2IoPcn2dUvr*6zcxtIxsNkXA9##*o_W?gJ8hJ{ z{1{#RMJJB)>A?P%Z+PnGkWR)gIwaRVWtj)|dFCtn=+EsGe`-f=81Guve31H+ zP$_nNe{kJC+{*Tfu;B4`b$gqhI=%*G`$SLq_-g4v3@cnzJHCWXO_9}(=TG4aGWqq# zH;>I$nw=DbjoxG=FTap&YQK~+CS&Te$kpw0RjHoi*+cmT_krdgKQvR`K$n3z)634M zDc?%H{`l63V4h93Y>OFks-<6~D)k&cECa>lYR7}1X(inZrQ6g#O{FY4UWP5J=9q&~ zgGt#owy=14{qdFRgkLp{r3&p7+cr6HQv5J*RjTEmM5VwpTveDN)T`~BN44~Pt$rO; zp}pGi3zBqu>0?xYmkj!m)$;zylfc%eoP-X-eqH{mVa>;?6DkU(omYUUxl-i3+P*EA+qViCB0?Y zdDRbn>n*A0LP_>23*sK0GHwoSFew zG*n3`snXv2tU>qnM|2afsm5x6a&NJbM*WqI+}~dgki^6rntxTk%mLRbhR*BKiigCru+t`Iz?9DGP|F^hHHZMKt78 z1g#kf=w*u(u=gPz_Ve(>PF@W67kg5;;^EyXJj}zpQh2C`x2JHkhqtD1lZQ8_u=tPi zHWJ?ZAP*b#@X!tz`X=+_P|{hxJiNgpSX+o<^FgFkJsw)-Y4#OVn<)8 zo$vy}@VItWp4hQsrOk#zdyi!EthpIVm7(T}9nCB5Zsy%6(h7>-1iJ%H2skC6MyK9S z3pgX-tbnrv&JB2JzyPJ6w8Y}mcn9GDlxljF{%$SyJ|72DKXn?F=_)bTWc{UdpOcqi&48tv#}N< ziV(A*7Sru9x71=pMbg|{iy7rHH$@CDm+Nt=w%?lRu$9((Y9Nmb^y;W5cJy-4tXZ2} z|GnMRH;jHcw`J8;I)b#xw5@zvRxybsaCvjT+59+(A^KU zuY#fLG%p65>su#;zBTCEXk4abxq_8nQOb{&I<(#tnTgfX{ZhEHD@tSYE6Qj@Vj!@X zu5?{o~YYh{8Grw}dn$ggOF;Y`Kqe0pqtT_rnb*u?yt_Q+2C#4=Gom48K>DQnkN@`c0m z>pI4!gqv(aNowLb?cf({ReOF#(a+>pjGUBGE*xH{YCa6Br61)NkIJs=sE&DJ{KSmM z)izAYFi(Y_)0tf{vTq1F;@FI5AIstz6Uf@6<2#5qJV(DQC+B{$Q0=Fb(|eEFON)Z< z^scvjPmDGMt0MZ2ah(V911!PaV0nuVK{aAo- zlJ%A!cipESF3$crl63-(nKq4Tz;!>kgalklEnN4T9(Dh?Xpfn-D6eHM4%Fv2CnQ?mun;w*f5M?+1zd;dN^_{+xTGo7)>OlTF z1ql9{r^t1_igigWf)d$#G;KHvVLz9EsRtr|?=gt5*(pZ-(Az@xSt&++(0g=9B+Ip3 zF~Tz~rP-<&;gPhkH0lS#GbP1rRLs#RSuv_(912f&N^^_S97CG*HZM_cb&O#imD1d# z7}su=>k-8VX0}4FRhS~scJ64#^4g5jLl=2>s1WI!5-EbJn4qfsTkD~&;4mYodT@Z` zM9Zp=qVC*q*Ux#j!y6%cFdso7Q(`*ai1xDH%|_)faiwIXYX%($IZRY$XrF>EJ1INE z=H1zhK-PyhJOe*3r>Om2)KdTmq)?1N%5fvc9h4*X?7f$z5C|ba?~!}&U8VJv<=*7F zF)H*-oxB)`g93H$Q4n)SbF|Z$YjN*^wCr}0 zw`P{Ao%f?il%t`2M^xK(OFJ7kHbWnrSt?e1^V33jlh?G-O5-KcI&bIG(Vo5`%8yi< zCt@J6Tt|T~6#1m+`3pXzt)-C>Gp%z#REB$4=D1$i%o(ZmKCB>I zn^f9H!Z}rG^QE<}i4wuCFJX(fp{KEAkknISh*RAc|LcLfbhfQV*|0LU4u_<{Fk?O~ z%DN&enpWE$G|S>*6y0@3Z)jRA{Vbo_9O1qp%w($6q-yCtDBhecc8bsUx$lN&jkUHU z=BQ^a=P3rQ@`GkBfOgLZ^p@}F8?^V{?!;B0U_o^bY}uq*Al|3Uo2)BpeIOh()w|+u z$t)oUn^N};HlC<;CaNc$*(*doZ-8izFhpf~?rz?DfArzr`*;wRC+^sDAEfeyEBs&` zdc@v)=~9)Yaj$kYulgp%3R_6=zPGfjIa@v{2khaO6t47(+ih#o)fZnZj_;5hD#npY zhbfJy(f79=*u|+hs35xZ7Zwr`W@Yv@L|)!lZF` zKj;g+>n(pfm;s`zFgHw%r(Tv=qD<Sryr$!nx(mqQU#(HdV3y`giwsB z4{D<^neo=0CNoqCEG2bpCW8nP_XwCv^J>9lg&f&VSBL?`Wsh;Y981`xaL$x)54C72a_WWP_z+8zQYzO-s%`h>GlwFY zs-3%eV~uYbJ8p7Dh68Y>vtBgBEU)S}3iVmzht5wE=>%gC$tp3W z3&CJYmsLUN;D(S@$UH3ogfsO@&tpvkt^j;2!->YJZro>NsMx+C==mY)f@gc4g}Kzo zz4wdNCpn*s<4I^3JS$WbN78*_+~C+=a)VkVA+@oxEn)XQ(4X5M@VvVK{lz7?6ixYF z^U!)#HX^m>v1aMMCR|kjZ|}n+afsJD%OAsAj zKNMWyU?`X{X&eeI427fU6XCDPTT?n3$HFnRMwPKd*6gGsYGjzvQt0~+63-O%ixJzh zN(WC5yj3+lY@qa0e|(0{XEs&K-!k2Yk+Y=v6h;m`H;)3xg^-5J%q~=VCYza5rfTai z@~NnRK0jeo8q2_#oG%{AI7r#1w!#T&J?#?$jS?3*)iFOK%OvuUUe{t&91<4oQG_7X z3`Iy3ULP{mEgYCn^nRO*_!vkruO9(-=xxa7-ZJv9K!G6bF03TtZ`!!eQAxU!$0{1e z66Y?4K>vZ1R?>U#V_dh&J#Vr%`4~wWfFlSl?Kh0dkH>I-%wV35rtVTxxn!ZH2DxGoCY#PqkQ&j8jWSU`@C7H4@*a zu_}5UHfC38zM97y4bpbqCTJX_{&K)U$`CcZSLXIm??Tue4Ocb}QyaOB% ztG0(N+vhYJxpSk&1C3zM3_XqMy}XuHJsQDtenvB#v~{Xh`Hl3FO?BVS+tzUVvCP`+ zVr{~io)zP?<6w2nUTId7@^hNAGsbg$B2qALR1ZjDq1X$=Nxr*>zIJrm3VfPma$n9%gLL#Gxs%(B8x- zFz8cC9OK!QvBM|EZ~J(DCE8k=7+qBhLJlx7mLKtXk@3v3AmI@xaxN+2f(I*12!AcKFq1J@`6I| z&`XKXlPqx>%Z*cZsGqb@d`l11jcM{yHT54T^x79Ydmoh0OLMYD^giD0{YI>2kvlQS zu~gl?_g+fa=BT#P~8?7-$|#BNqeO=3_ke+{r9XYL!bA(>7+W`^K)Cxmngeq2KY4RUX=%r@RbIQ&D6<*q?5?zgMS=A{~ z@_IF|rVI?YVz>F9$=!7V6auLMGY8Xk0`q>9$l%0_M*G+JG(Hd|?oc6L(Q+7DMn_I?97SZa_{ zd9e#o6H(N4vlq4nKyozzle=V>UNlH3>RelRs5Tr*AT3%A#+^-J-06+;Bg)O#6?58& z0IB${?!K%XOGDo5eA86U91Z}U`NNlzUN5;SIfh!zC4WtLnPI3=ddcvu;b@7}e9YV~ zK`lnamu-7nKj|ggyc%bT)Y!t{y#iymsYJr6#x}?`D6VX1C~8?vRu7;zwX8Zxa_#H` z4RUP&Ye3uAOhs~SC!Zt3K(+I`Az#L`*umT=(_}UW)8riaN-_BrYKY51nFw5osg|Fp zmj2V$I7^zzEyoX*KJ)>XiW#1eVh6tM7iQ%g7U?EU=7ri$sap6T&q8R&4*cS_(66dv zH2(^BKBrPGeS7Sr@!8@wq+d3tLLbZnN8O|z0xzA0MBs%DzCo+%FX^bu6!4@exXhd? z3CgIuzP+_uE0Msv zz-!e{u33AO3iO&|-I{NBSpJQR^9Io%7iQp-aDxD1=7d&zyEbfCMJ8gKpoG{qCnO0O z`ih?%q}2H;wNc)czYDcAV3N2yLWjb%!WUv~;tr&k60rPy<;OqTwlnsLZs6?&oX7Br4gfL{e|$EyZmD@Iq}zo0AOH z3oJi{{psym=QlU9?C0OlB|xoKSc;Pkb>|$ zGR00n%c>@c+J}AsNu0y$R-+wnqyu9$THeSv5fP=K^&w_YVRbq_JBgtneEG%AaGHs< z>q6NEWfp0h{6O(8rb+=hdyqZ{cqypV2UF$U6;0-iN6B=#%c z!%$Ev@Tnt_PP1`e*3-^sTxPUa0+DBh6ZSYh6SpA;lDK_>nu=`96v*qBTxIVThV^FJ zrH7301Ff=E5Oq}QeyiDGs8>u*H>0Kfn!@=PPfVS&B25wp!n;csn;k|20VRjl6*kHUZ#2 zF_NY@#p;ku-5wMq6?V-|wPiVxw-X714a(u7v&Kh?)Uulw_I^V9@H7?F9TCQB5V7jk zn&5vZW&w2!vilx0y^Au;6>jJgee9@;PN-?N*^xv&CuQ@0bX)Gd?{ij1HylBir~P*eGSq- zDcW@hT^ki`43Zpl{ccF-@mLm3$-WpRn@!vX?K-!Eu5LGARzRo^)kd#R#(Y&&bAzkb zlLK8bDJwnTusG=2_Ph?dMn2BFQW_^-gLL$X zrk^@nr|4=^!tiWi+hN<&!!wi-dit+UByC^mgQi- zdbx3n+Cx-a6Hdq(+44dUkKMdMOc31&mqsS1*nJbFUX*|@Qj7B8v4 zOWeRzcX@h3)IX!Tguy<{%z+t9Ym5~N3+e%@Y?M^c? zO1yg5b@=~^u#Zu0wu;{%@|hEoxQ9Bvb|879aYQl!Qr<2Ctg|C)IzXuntc_lK6B=ZX z+S6W9>9Cn%z2mt>nS4ShRtAtj(R&{X>LAYdTiA@Y4CnYFWz zcJMK-chJaC`=^jY(on+j)lDT5wz3}o)1Jeol2|UhwDowP^}^xS<5yyTVJ`7SW@1mQ z$ILEj9x);wtBg(k<`OeQtNyjgM0?QPDMpkm%r+>EdLcX2tDl79e8+m9s=Qt;tM1n< z^JkAk$C{Zs%`y##J2I@&q2}i^-JJ7y$mwzEKE+I?nVJ2k8J*9NhAfGWbz9czj6}ZH z$!GqC3l+9!Jr@FC>(>1ROwchgj3fIjz2HKH&=vDcm~*gHZ}S2>A0LYsPV6`1@~Hz~ zsK9>Bor-F!Jd4{RY4LDbi^Q$aUtOiL*ZI3S9XRsDf%W)oP6z4d@wRWs*h$&c_H6NR zn|~zd<`-Mjaa7T-LckUK$xvIBsB_bJF5lD5Vrq;K788sKiPe6SQ~Tm_VBr976@if1jDSr;Ca&GWSiT9diW{EIV$?}kH zKd7pRKnWU}q4@}sS^Wz`)gHAiElac!ufz~T9q9`n8LGyKdJQI-O(v`8k_VK&XyqjCOB6L@0cQp`sN>CW#hdzXQC=T-X(eLBHBpgH5~RG7(v%jI-Kcsr zTpSGoV?NSMBP7&M$%;z{X>0Xxif(XhHe*G-`%P9NtoT#SQ|i9K=ys}$j9rUZB9+?< z8r>pnxElqK%XrwQD_k9Y-h|&E4F-QC2B@pd`p>`tc^)pUUCiNHsjZrPqUeoSfiya<&Lq%GR-Ez)KIrQ zl2}|HiVPLXXO8SUf>`w-+shBLeLON-(qU8Qe5TI&)0X>{b5lB>BH6<@vt19LNVQ>! z*ibS`y%c~p&oyyQtP@@>u+BoonrELdx=Bx3y@GZ)vj0rU?IlOD(vc`sAlc(cdI809 z&G$e>cPgL+w&=Q+ndEwA+iQ!wyFKrtkypW}fI5@Bim|*4$h*k%fnfm@+{G&@{{Vn? zX)N{)E>><-z@_YOvskkUMChT34eg%05o?7y!%UWzZ4K)+rX%Z={>wJ)P74j#wgP&E zEq15t*KIbzF_maVt#okoW`RaqU1-uy;3>iybDb2Tc@Swny=VgATa-O+1-j}(X~Ic8^o}#K zDqoMF7yna@q%1&%V*meUUV+Hw#?Ya>H0;Z1T1>q?z)t;5$`1RhfJRRW?3ELv_u$be zVFuersD3`>vY)@$!wYWDO=!QCRN_htEFiE;S+oJQ-SRT8YL?upfb5W3Eh<8NN%na> z8qH&iDb1+bjcS-qEugk*LN$A(YFanDBJx>Sa#D4@-;>nB@^|e^;5nOR-*?|(v+QfL zErnE_MI&vN6Iod>9zM&u*tRqxvK?&hNx4L2pLf@poDQbfbO|cs`CwrkArMp7CRvtc z&WN>H_9$vJDkT#Ab)AmO0(c1U7rHZGYf+(o)yho2`PXZM$X7jER()3U??bzwy$=KJ zf5rUUF|_fPT>bu6>3KhZd0olQVA5=xd3}Pc&i<7K*E|ZCj3=hCY=ZgS7EWNMls;9% zW|xwR#B%}F+0QoNXK2!7-vZ;9r8dC=wXZeFpb3Bs>eK4%Z;;`6)`skXH5@j`$jCMr z+gXRzj2cbO7q-U>HoeBCdDm^qszrXqaBx;Kl6gh*g&mYRMP-(ro|s)RJo0egpMup- z)wZ9KLPU)$B;=K3(8T;=-R!S+?B$qfCoCh%u#2B9^f~!@%&E4KyI#)8%_=F!)Zv2gT0K(Ap`SAa+n zhH{8bSk2;mWs zgMNyDvrR(fR#PDZ=jOnfj^na=l<_QDjmE!1!G@n&J+qdows zdJ1wlMO?Xh+$0R)1t98SMhC^$c};+>jW+G&%I6*dC{3v;Uy;2% z&r6NaBQYAo%<%gNHL4LBioDpv3%i7`@kDrc3UBc6t`rs%^L~2@ixUZNC2Y#ZW<6-r zQ#wYmMlUSU->?h%Mn@El`@(`PB9Wm%ozS{nl{d{IE-3A=8+jt4`z%TZS9Omjx$b}x zrmuR^VemU;sdK0zS?hDl}pW- zxBbweo8vnM`tHOHPrXRh7`e8eCx4K(7+!6DzQP~mB2u_N$O=pEmNl9CgH$xCN}azc z=d!%x1U}P;DA6r8Fx#EoF&lBIL!1TVxKX#Z#~eflS^%0!Xaah}RI6!89wOy$QG2@h zL@bZRks&v~92LGI@q5UpO5}1e&<&O6p?TzFBx^Eumy7mNo*qFl$$c))6?U99Moqwr zKgiBqAZ#5=U1ke~8yw6bq}QrC;n^m6dZa3qNeCg~#rF}J+rZTx^->jPD8FyKqvF)+ zH+(F0sDK04kMe92HS5sjwjSkiYpI-7dXeBA3I5@etBbxNu_pGQ_)eKYl-V3ak_JkR z!eb`G_2Y(H$Q~8Sx|$#cPIWOyyy~<Xm*NdqlP4$%GHN)))Z0UVbi8gNY`0$hqWTrV)6kzio2kef*b zx-CMo#di>ofYB6PLt0qTrD-JQqzKErEvYw~9LE$ua)h{X05rDEkdQ!}4Wyw4w|njh zmOHt06hl#t&`>F*EL=MFM{^4=L9-q}L%NmYh`skiqG$$alpi!oDKvH07K%nupPP9N zqICe}<{M9531uUa6D5wat|jea4obtKmVJhvihxk0Q5+AydPvd4^m>cqodNd4^<~lPLk`kY-Kj=A9HPG2W|I zu+nr7oFDiW2(CKBG&qJQT~-xUm~lF(9bX-T^~%|E)op(ONt*cX@0RusUQ|o>&_4&2 z(r1U>;|TBfuu%6NhwkH+ZeHxG#azlGF?(t;b3JBvEoQdIsJjBsERRvuBE}?AtggJQ zX`W_tElrQdsP`h*6pz_Zi?IP6gU<1EdzzbTX^b-N9ZYzr{&Kyqy;o^3N^KAztj_ zN9s)TlCjC1M{-6^?jxfhuUQzr#86@Qic@nqkW49yDv8M`N1T-mU->yBBU$FoBTe1% zWA3V4enltVBgrIIW481v{e)_Y(=aoQ%C121`YvXsQ7j=A5IGj-L+6Yni*cSLI4k^y z1^z)&p~L-LDBZ;_eP%O(4@>v@C{iO%mH1`-NQxuaOVJoc7(4|C#4)fP<2<1XCG6$= zNbYk~PYQS)Lli&+l@@*^Et$vA26Z-Sf!ZuviFUoxNeamf=Ad4sa0vn;wV7;=Pnz;v zy-rpu9`=c|+1YXiSE$$$*)4?b5JWZv1$Dv4&vuek5oV~`<2ZU9he8F8U5?`cfN&`2 zI80>KnWlC-j)DA0Zg(7a1r7xr#|)mRha#*VyBxn?$_Z*y)CRn ziLbj0yPpu#jt!3EcE>S6AmOk*Ibi{rk_p*MY{}iiYihDyAVx`Hwo*Zy!qAqSuz*ad zg{*Ez&YD?ozan)Yz1fkj^SlZ*u%V6I*ku~Xesz1VlE2hDFJMHk0VbU(RzkJG&@JNPk=AhG)tdsN6hQzg_by~l+h zvzXl}&1@blM%`j*W~G?zDb0)&qi(S@(^Aalltu&F@N7(Jrlgn+DUF7lrBOeH_9WU; z=bJ5t8j8m)%}t7-UA$bb$Ek9E$oAL}^dXpB>3#=$WBs*QbmsFI?N-Y-wXFIude9Ab zy-3-~p`=E$Zu!)PVC|b54_Hi{DwAmeknhjUNiNCEn%{R>(T5U71OIO?*Me9&EG==xKo$nU{*Dh$1LR3gq?(Ml>u6h&` zZY6`JzDP0x+Ewk|A*;TL5-?wgf`VL~X_d~~I3!P^RW>9$_RuFvAIeqGGRkK_>awKk z?g*DeTF(;VMHK#r1OF&5lQkXLU0&vP;ZQt;j?9I_GjeuUL%($2lVYYS$0Vv9znsjD zYCf(xl)%10)wZ45k?o$8jl(C7Cw`Ygn zk5v)28n(WaE6H`S(v_ry!WszfC}jajS$k5Vp>^9oy{gXADfT~>Gs(tYjV=!*cWP06 z&!i=ppFc2JB&-Nmxq%Gf%nHr6>Fpwy6(8eh9!XQlZ(4lIfji|@a+9&9e6_B&Q;d1* zDWI~x?#nxG&X=e(Q|H_G&JN>fYAIjbtPvG_Gnv}!J)CEwZb=i@?ENCWMccJ}wU+zz z9GsSuGF8eBPA}$kxQ{}3A=J&-0Kt^Q5D=kZ7h{Qa#tZcIrOF-xDRt=`F(zXe)M?lA z>vtkG3?YHK4ea8Lpk?2n;QCOvgJpD>Hl2Fb@&pd6-8(mAKD{B5#V$e3#9lG=*)e6S zbXa5EgQ-+5bV`@DzE?)$dO<_snjvY6im)v=-_SN?Lo_iXjWM6!_7fMFugOh`4<(I# zq=zTd{_AN(O!S1DS$tI<9vj)vZ%9EO>#oK*-tS&JGuPPgm>L^)95mZVbd_4uD1Q1G zXJT4Ya%v?;)zO<(*Xj;*n>(KrDa58BlFEMsd4f%slyJ(G*l=;du%(}w7Yb+3Y8!s@ znk9)KvRdRWZx?fDvN>N2TMtc)Oa;WQ1wWU_pc=u`aJGEsm9wcjE@E^+G)bgwGp^Kf zE)Go0wgVG$$p=1l8A*OFv>~URapBWoWan-?=Q_XXroXtOJ3PR7a)yGj?s{ikzYq;Y zL>uaBYh&L;SBV7=|I*hE90-SpC!4JEYts$PO9c&2fW`wHiIsmT$G-Y9f=M$^YO`RB zj$)0YE@xEKv$IbtT-v3^A`DoR%BN9xM_E50b_;{=B%nX5L50YrWqM1V7$UI;?T5B| zo^eN3LN4p1H0y9=W!iOvBP&%zy0lnNP(3Xu7LbA0YT-D^kDsX(N$E{&c>IjA?;J5Jq_!Is#4_zR&^To!HIlyhY=gjG83Ny3NSlh-`RS1M@=iJC;W~kjJb^(}#5h`El0D2koJOA6 zG?o*=DSip#qm)L`)S>QRN|lWvsw2ZTRe1f(y=!Z>xY^yis)(`U`q0#-+T9+o#r624 zY%RiGl6(*!Bz2k~Vr2P@cKFDub1-FmK0l`YXG4Y9FH~{hxVT7Wik~xXIG9q2X=D{{ zoYGwjs^;>1iw_XrphKCk5(7^tAJOrCFjT_{(p!Jk_A@|NII|N5C}HC&rimfJ{!~ZN zI_g@?R{fQ$-O8TqKr!&b97HyHW;O|e-~D6^9-Hc?s5Az(Js?u;eE@X3gf+Yf^dE|M zQ7yfPHpMF&l6azHFqrQqaH(RP#^7?NPHNz9B&INiZF1ctEbzB#*lb!d3f4=E*fb1m zb~7QP*=?^obu@E-|J5v4m}7nI{6nqlyI8APjZNnWUaF^1xSV%wY#Qx-{91`Y)?;Y4 zs%&Z0g#I(&fFdU~AZA1%U?`=QteT*4e6*TVQ``oa5nI>TjXmZDv(b5o0m!(x#aX|I-lC=<6Dh6e0;0kHok{3YvQGH zH>0{WTcSJJvy{PwR$mhr0S5L`sjm3{;rM2t>{rcvMAI5^1q0zpHOhxE#L$q%9$6dc zF}H`Y?KccwQbp zDw8=4cMmAvSlMNU`VbU~37PSrWJVGdI;bTwneR6jjKruJ7{%nMGVbQBv~77_scF2D zqoVD4tdksSP3$`+$)RE!=69DI%#Y@*NPgcKO{$~Bh3NT`VuMDgK$uzsE{#FS8a@CZ z3G!L_a%`OOUsgZvFE#QrkQ-^iK7f9VOi?9k^S#Ry)hLl&I)NHwX;kChqqN#ILzG=U z`;D!H-pZU>$@Xg~4dC*!yaoqkx z>tiL*pa#$xN+je#5GTHH%sD3yC$rngxn#nAWtQ zfo%FdAZuEXOEvW>1QH22F}kI8yHq6WJx)^X9>4KJBN`gZyd-)s(1im%i3F;Js4*{~ zt=>}WUAhgGblbhZLAoW)N#4Cfx^=9vPe;0((x)TO;80^orHNdVGz-ENrAhj9WP`fo z*G*iJ;%k!=xl*D}M}}_6rz7pwrYf3_D^jQ_Q@H$gWs1|Ax+H1-)%0faL|)7#hpvhW zT`No`T14A*kt8a5aRobfRFk*`B*w5_SpQF!-fFtFxtJd&?bL-#x-;Q6SMrV`jrT?0o82dI=%mUN7y-NahP zC}~Dqp{IHStfe5D5Q0LZ(%s#Ns31`U>efKMD);aT+Vujcib(3WClz0KcHwqk=saqf zOc7zt@FC5+N0q;5k$Qq+g@fv7)Yr90!Jt85AF0QMAu~|t% zz0=)$^{Yuv^#VHFJ>34oVzfWK-p=-K?h=MlcEFK>^Jojo|Z_wSC5lvQJR{Rw!qzL7Q>IVrt_|)W(_GB{138s5UOqkXk^US;FF% zg%vEH1!^XDYf8V(XiBk`yYMul6>RDLe2IL>=nZ;f-0Um;Qg)`rVrjLVXi+zx(?)MA zWwoqbixkS|v`>a?VljKM1kb?jxR{}nlo;$*yV9@whH&@ZMJ+aA6SaQCCq%6qgM(A3 zt`tnlR)2&P;FJawHGT@IiJCIIeK^JUC{;g?l`cAHg?NrMPbp0yD~%D$&%^zC0*JdFk}56 zl!HP^7(ZX9>?6nv4=qNlhJ`G|5`$2*-i3!2l>sivwE7mB@(SU+M$y1cu26;>;-Z1d z3yQ6VLJiatrHE-*ejo0cWiu}z(-u!Au9;YO)~V*0MY9S`@;b!DI(IgMY_K-C)U5H- zMsUSdFg+sc<+*Y{kM)O`-E*b-wl)bQ&z0&NO%o>5MI5_2UVMK-A6dOWu5PKBeyCUt zvS_7K!FFgS?RjZiI~*AuDaIrXPw~nRZ-$6StHd%OJnTeI<}fm8d1%3Y;l045$VDjDWcuk443Go z&jC)YmzY2yog~3aE8FO%R<3p(dNnu9mKRIsqnFsfi!bVgDm#Y_W(54+5WwT{@~h2CpiWoRpDoY9(LXK0dNjK@l)bL37%)9nL2iqx2=iZSE0? z z`eGT9KS{#LAkygftm*`^Dgr4af0m2zXW7#}s?f6c@QSRx0A*Fsv#K}9stC(ElB}I% z9a&`E%`37#3Q$%B$x0qQQSZYifyplJym9>|0e8$$Pug9EFu8yXf%&TDfQAnZjYH3D zoCCHs%mJ~{8cKYc1JphZcf`Ro0BfI^18_y}8@#TkLzpd|OoO~{kSMg7Cnyw?TI}9V zj%+LaK2cn*_QGN4Daw7M*{+lwvMy4Lr|xIMGV0PrI_`8A4lJ0%1F+sl6_&z6mgjhJW#T44O{ z3^g&$*pwj(+ObYoZs<3Wku7Z(_m)P4jIVSXqXlC$_*522Vy^@$zLwK9w(#K8`M| zgt+ly|CQ~P&)7D2q;l7n;l@iHZf?BfVtFnBxmdO=UUo*#*cxY<({^wi zlT2aP4$(9<+;~|w+<1A-s0%g2=Vg0f%%&&7d4AC<4pI6q8`#&3KyS@SRXXQI1Kq0itQ`!9lUbW=T8aus3lo}{)Y8`6-Gxh$lsuW7 zY-;ak!`ZFc`7sx27Xnq0;kn9YuHv4C{9E?m-*QI#v}k6-_FQp2L;G`~Bo_BG!puf6zC+zsnRCliHiFgh6?GOwGJD*T4!k^(c#vy z4Z>8ocNRz68cNYZQfOKI7E!k-o8N_{2&GQ-h)Wpmk4wpz%;qw$?dP#^^(5z(`xKiT zI@?tSO>W{3yVEeCz2@9OCMFSa zpfek!nVZsxq@+1)wZ#NCE2R-x2imQ$6`5!NcZtAOmS|I3ZTX7KS{GM(wCf>qS{jkN z|B6g6eOi1?$$TEOL89`ijhY_6{!qj8n07_#PFTiyl31Z(z0(R!o-8$K$dje5&}Oni z!{j#53N7u6$eX2kfR23;JV3wXzDRM%#JyQ+h304`kE03dIPHrFU9m#*zS6e}i)ozs zuY#9nYF12&jVrXpa;WLkrrchtMXblj)Unl{HF@OHw=Dr3#s_M-9CYfMLLnqqcMon~Vhi(u^Ct<)uA_fS8 z8esB`E);?ZPBf61Oav$dN{7jpmSIUmn?&U3y$?ipSywH7?Ul6PK`CCT9|2go^g zJ(ubY?6WQC-1V^+aH2Q053>>}Ud1kXWo$aqt66Z0hh&q*kZ^RPa9}~BR8GaI37kUY z)HGZsR$IvQx(>k3(q_oMhpt1NJ60&=W-8sa%LqY!3}?H2x#oN_iO&pusFvKobid8i zK7e!9K3ErgK&Wm)d@AF&XLMre8yc?wpld<@T4V7=T0Uip*Y{;1!vN7=*iC`&C$+8;ISPXQTF3Q2j9Lm9nA2)$LRP+lG3VNv$gXGB)I-mReJx zSjJ>htI{jQjgwj`TKQo{44>4}QTN_|lMG-lZtK5uBYW}R_nfO2PyagFL-|f3b+fe) zcQ)Z89+@uMKNbgDeLTuq$X||;)HW%Wj;udl_Cy10G^~x8%g;?#f zd%?oK88{DW!joRruoh-;4RyEbtFIMb5;wo1&`Zf!w#5?ZjA=X>Dz_WR>Cn}g=0bZ_ z7C*=-l0g<6IK%c@CRTg79med8$>Zfub=tl1$Ftar!;{_uuvW8=maaP{kKPgFLaf|* z;Qu4!u@?G;4XmkX{rM6v$!r3J&zEqN6})4;d#qj1mIAL{K92?qiYlHM@OmrFBud*d$6 zwC`M?Ko~IXC+yaPfDN{kwCpdz1sA$VP6I1iVd+A=pueEByS>g^Gc{-Vh4LH4T@o1>^9AoqXY1pP1vG!$h~5^ zIzOdDV8<_gY&{_7c7Zl2Pk30uQ*y^g*@ zlirwLC_U)pkAR9FX0UF;fz`};g=Vi!Z`JOHZ2CS;@3(0dON3{!P~(qXG&rx&WZtS_ z#5Uzc-BLg;b0A`0p-GKlbs%oI!7DT={5eJ*)Rbf7QA83W2Id%Xwjj$9>40E`;C#Ua zf{O)f1%rZYDD?=W2_`iH`3N^SBCDKVc>I5|WRA>d`i4dz=U6g_AL>N;VQz3G041IJ zvWq_Vc&SI_huI=y66zR!HY*$OVHPMq>uDp`HQ9T-bkt*#ze$$ZgF}u@lw4eZ4{>ZV zf6w3`%Hv%Z7)IHb4P$${VQjn5FtRT)jM7ZQ__D_^zTq{D$zu)U;T*$w$Zr_QQw-zs z>7cJOjGyCf%@=D8V@I7~TyTqFd=fN_M{hHX50)FoFPag4g<<^mF2lHPonh2{$1skB z4dc9f4C5uV_s9PM5zm@2<0?<~thtqAJri>#=74=p%bm+YHA{e@W{pAH)Lhq)6RKMo zGIDBbLN!Ltl9m=DhnCHa+G2TQs4fT0CbWcVZobXPxw&!KvbyCV#Pd0y%is@LVT=&} zMZo$;g#e_9@e&}C9(%?=rrk!uhT&cKOTph5p_71owmW!{rawO8@JIij=y&JIa?V{uo~&{wS~gc>mcpX|&x+K-y-y&>xCS?6KX>hmD;E zI!=ba%9yVq9`tXgfzA!v3}Y+si}<5lOb2z%G&uRCA{|+ zrbRcmG%c^Ki?AOt;z%FBB6@~XA7!w0QZ2<6@v2x7YHsEtQ8CjHV8Heh6GpCG%sT<&uRR+ zhfi*%s!t_y=m|BP4@deo&sM!?D#Amxn^d`wFwDBIi7$V8KTfOQAv21 zR_N-i)2xW<|L}@2=1O3+JQ(lYk?wRJo+i34j>q+*} zgr_HYCEn$sn&zJ5RWOC>m*284c`Zylm*}%@Oc_*uI}i6H&xR%S)aJ8tx%Jd{{3(** z;@_o&e-48o_byJ0q_uaY6!f*7jP#nL7%C9Vz`L>pQzbGhv(^PCo=#5OMAA8;D#G zNiKqyz5~5|Zx5X8PIh zQ7M#TV>bA-A4{>an1$umXzHvi_$9o9EBP9O7gXxgCA__x3&4fCY|OvO%3@}hKTI(K zL6&YuApBfznJPnZfg(!Lhm#rmTOXrVv|r6|36aqrfV=Y$-jU>dypi*-ygh)O=@jHX zL`XqRPjz=}qX$^pHtok!%S(f>G=j76LizQTnWKteG_#8Fj)^c-O;@CtsxTtuRGD z(JJ8j@<{K|S0laAg;0E->MGtk5J_GPfpof%rbyO$knWBLp$lzBC1m2eFQwZ{Gj0B8>Y?!jtuej9Usb& zqoX!EA8=oQ{MlDj@GD3DfW37?Y8;bsP9~0f@lh_$3eOB2y#XSXS*mcA2R$Hk#fYoK z#ooezsu`%nJC%N!f7EjsirfP#$C)F$VN)91j5oZo7_j3Y2H?E|$YMccu^^TQ19%5n zvST4|iVh@w66uo+%i&IB#4IUg;H)zo>r%=ec7T+-UePLtzZ1$Ie#TAQi7Y@}K)Msj zXFE`*&zhHFs+PL%c>A%nQ|9?~LlYSdAI6%HL!Y`m4~1EC0^#%zBZ+K(P*2TCEVk~B zH!*Fk}L?wrz>@T8sSS7I_n1)4awl z%I@vL#f3^KW)|y0>&PC}MzbktKbDRitzZ$1x+tOT(b{FxUg0g&RZ}uMy^5Vja{{KvPU)#&NS?}B1d!S!cwzmiLs0~FX z1nv1C8#-5XEHu4!03VU+27lu#xHt@bE-G4ux3&yzQf(iP&GWOdyEWOZe0;Or09D|frvqUW$~WV^o~*5ULA%h*|sYBI^r~hWAiw}-`VBf$e}OvRUCkr)JrJ@U(Dd!Ku~rz zQl*Hl3rPE2V$asG6zqF}0jnhyUfGI-)BmlE){I@`4S7RVF(u$8Jh*W9td)S>Nzm+R zsGOL*a6bf^;WAOs=}x*#7v|_x+{G0@DrT2M#fvE>#if`O*V&S3aj^^vd!~`%mZGRs zP{muc$o~7Q*u_y~=~|V@TU5T$g(5rijUv-t=clMRCNg$?ATr%4a(St$e^Kj{Dq1xk z4Gs>q2+;$$3P}o@%s)`RnqlcIZ@^*zM_C&I_ z!enMq73QcH@m|v+<39$rGVcW^U&PhhUlKvnLI%>(Mn-pmaCdyw#RiNHk!0FLlDFcm zJ863`r_WJ+dyQ|9_3D&n^9SygCz=rX0sx29E(KUMs$dr>_65!Z8o zLVgc>E)g~-{pBL~M1)NbQ-7UZt!_13)as;$18@4hRu=VzHmckj#gvx9*guMCutq2W@K#`1KzH|CBShi!mulwHa(j`6@pdzwrc=WF?JrxYI#vv*dwY_}hfhy3Ib#9r znsemaHGN04p5OW{IC%RnRt$8pV4%Ju?hY<*BgX8AQg$Q>cOlJ9(fN%$9Unn{Q^mcw zY!x}tcN!ZIIvZ73K)VH@kG#WhuIY%DP+(YCeFtT&R>KPn9pMJ};MF>##-us)6HPNcWJJ5}{ZL;CAI zjS0_1N1q<*k8}ahmBy|v1=c9WZ|+B8m<;T$W8XYcN#KfCW9VO@LZl%&51pNfRgUOC zD1)>=I=<)=std$?F4B9B`1-n9XT`_pV~i13BC|D4H?6Kn-_ggxrH@*T&II4M^%l7F zMyJts=hu(|#20OZDxB?KKl*v28f#`AEOa-Aj4>^Sr>VJqSxtkde)-b6nwI({^$qo* zJFkKZ{^jQ7`0ET$Yg1EQv*#Q>wEK+4Wlarr%a(^!C}ro-K?NwxIi7%yxT&=z=((e& zp|wt}%gO61!>DMkhg?f)nw#qpeN#1>pmCu2zLSwXN_JFPpd*D;LkF^1uHF ze4e^Si+17~2Yt<7V}C*IEpRs?Hzya{4GwZ*UW~rEC6wXIi6t=$A*_=Lv$1e$w^2woNi#{w=^C`Pu$5;E!pvADa1Bk3age zpG^33KDOJPu(Zu|r$3uFY1?i1-bN1mv1PX(+aD35jMy`P{WKqx$wlD5#~)>5-eJi< zrehe5w2KX6p3MZb!${}YX}zY*s74tfd9iyd?W z%s~fz2h2?ldM(T=@kjkLJ>Lbc$DhsrZkRVa==)&ipDiDZvFGf)AuM(|o^$OLJp^}- zkZgWGhIuRg?D(I6d7Fd&1F#5zW`t&f`v*VK}eXEf1rBKJm?V#B$WFv)1DX=%xs zY&6l!l?FSToP47`r@*)^C)a1Rty=N$-R=X=j7%ajkiOF0xe4(WLj3gJSQ&~ShF%G4^mNpyorc2&yPs+CLz+i z$trN(mE0^`q5Jw4bo9$ZOKG#LsTrHw+)<>RvZ`5HTVHbv?UpaCxjEF>tZZ*z*4nU= zmNiS^-b@pOYObqwc%*TeBaE00?3baQATQ9|DP;Xl!1;hFf~7?CISa+TR_NP>#t{G& zZna>$peeXXa0@Uo8)poNV-4dcV$ZV9_`3yJo=Nu#zAMObNc&TQIVcyT{esQF#4B*t zL1;_xZozv6|4Hyif{zJ4D|kroL&1?~>>1BQ!D|I?5?m};FSt_hdxB339uRy(FcEzQ z`HmJGBgnpl_W6RPf{O)j5nM(@J~a!yLg;ls>Ukp(dj7t+KOp!+BEtPx=}r;?rkIfVX};6Dofi{LwgCj>7) zPlvxkFjw$OBGO+-MEb7>;1(jv*Mma;v*5o8J|p^L0w!Xxl=MX{SBBs(1y2DJeTK0N12oFr z1x(DvSPOk2=@wvO9_GeE4+>s@2Ab|;1SbhzBY2(QJi$uAC4zSdwhL|&yhreV2|h0P zGr^|>_XzG6d`<9O!H)$;xV4-Y2xbUgDmX!KvS6X$bio@0%LHo#8wKwaY!@^I?-sm| zh;s5zg4@LYUx6$)PZLpYo)h~%!Cwo$FZhvQ5(XR8`-Otz1q%dc3RVd&5NsA~6a1dw z!-78(>=t}m@O{C=^L4x<1;-0c5u77g`^+fd3n}zNc{FPvz;AufWCP7T!Rf0DN z)(ft{ydQ%lIk7WzW+zXd);a6U&Lm&%WHsmiJZE-Lw)yzgI~(VoP`MqC{w?s|!zM`E zAi7MwA8%qkE^zAww+o`*fa5bBEI?(J-6Er3ka{cZ%WxQpM@A#A%docQ?azXp@%BK{1{M3s?gV$|RJ1lYt5if^#aTvwmPdI} ztA=a|p^6=_@yzvjz?5Swqbj^x8LD-HL*8tAdpm8ADbb0=r9>*d8!yEo8MKmFc54b$ zHwg@s>YyHuxOgrJ3;xtb0T%e&n|=Zlwi|qe?P^1yoxg_T!ZI0t@?71lLuIAIy}fYb zAlP`o#c*$^f(;I0_&`9w7Xj6>44kI)hP>KCx1Zx>pIHjKMk>wuP;8Xujw3J9kFJDxX(%8iT7=V)z8FSkAx!QYD3XZxr)-anw zUJs69bhMHmqi}c3fl=k^Zk0#)`QJ1bUg;?XtB_k8mt*}g5G)1PU?pBCW!ZY$2Ib}u zEXrn=dtiJWM%HPF%;C7o^zADDEnJ$o(8UX>k-=vv83Js@unCe=rM#Zc0P2FWi59!P zoaUjtumDLphA*Y!o|JItCEOb3YM(N=>iS=9xp>)h{f*Dl2>C|t5{0}KY0IyNXt$b4T4HHhlfb}#goS#|4qDCRdJ3SG=a57Xw( z5n+(Z;DPk_(L~3tjGT9?czRH`DkfBNY39b)m?pzlPHdTC7=)>pvX* zZ>UVkdQ6(-8I+Yfk`UNmhR%m2zcgM{+?`fBLu&xFyW4|?gz{|&LB41hxw_AoaP%>} zqJIE^<0?1>Q-xHMRaI~!-obxllCe>(bqyZTH*ts}fPoJ>LHer>J{t2E8=KHy2mFC$ z6?zN$s|-F)e^20rJ}}=tUXzI?mc`sExePiVe_3VpE(oW>Ns@w3+2NusaH6yiV;_pw z++@ePV~$~TuGo51d*06eEi@%ge`Pwa{bi8GAE-uZn8(#RkK+>jP3&?}QC*ern*C>b zR5Sz5{5nT`j7sI#P#>zw6f;Unswa8|XDC#B*nvAQ`Wh&RTF$H;fP?|$4<)VAlE$gr z&(jxSY_FH=-qJaAihdvG9CVs9t?90Sbwwo#4LO#^r+tAp-`>*pM5`o_-Sby?i_3!l zjzG}9h>T{n2+fQUb;0kjGl0yj$8oR%@m7_iATYYh@D`PTGCh1);4RV7kq-(2hY!&a z2*a@Z`8!&6`?Y_l<(wH>CgmpLIylrkCWq3{?z6OcN<5zEzwivl_?JN1U+GE18F7t` zxUN7q6zhQA`nX@63e(&6F)lN~r4C$duCqW_f~IW0!{Lq9O0neBg`O}-97|*~fLZUyP2`}u* zih-q-(~2>37-`I$TRg2|+PT8Qt}@_J5jk1Hx@4Zm@XWbx$PISamXWjtP?2Laj^~H$ z*U$g23G04v@9kG_efH=lH_YBypj>cpLENAHo9$=n{mcLEmZiZ76w4BZTIwm{J5?Fg zD@}};hQ`h4cEMo)g_){gc#J>P{>2!f(XFee$ia&i^v7o${y38OEPp=uA^$x5@gcv1 z+Nj=i;~y1H#8g*3X_${@i*WnYY@s?Y00GwwZ49XY(d)yJ6}bO9Sn% zhrc=+6Ln+t~qPAbpoTY7MA%m$Yb-fX&asPf5{%B&4>7x z?2+jzfxyTg`+F*zC)0JYO#n$>K8zkajLscK8?tzzzQ@vLV`*bk-Ew0os8F4;RCZbH z-Ik>{H#D}?DgE;MEXGOXAUzSnepP6ekwj!dwb0CW(j2hS|8l{Vv`5<5qSO8b(#UHL zY7$U+CJHVh!o40y|KAgudllrX_8{QS!ocw5K!*Pj5%xR8eo*KypfJ#%+9QB_18DlY zgZALRi!{P>EuMHM5$*mELF`?bU`VGl#>e?%JbeIWG5q>-+xP+1vn7Le}u3(Ylh zx<`aoYvJ&BOze|Uff#P2U^d5WQ+G zK2sdFrdN>X|CBX7|HMgo>`gzWa;V}e^zYSrir zQx^}{lW-+K=d13Hn;JMZCLs3hWTJ2CVC|-4VXrKnF>8&siXnq0&*kS;9UiBw@u>L0bq;h(&=hP`xK+K zwrtSz%MA~}_uhAt!iA3~;GPWgAd()wE}`u$mDUS8Uv0Y(6SuUaMQOLakeY<0zJgcW zo0g!|Bciq7#9L)Jzcps)zCcy=4SOpQG+*APmeIN-3(h4 zk#(mjtNR|wj)cS1Yv*C}KHilW8jJBT4|5uNB^O17#j3N*Z0G$1_%flL-uS>HM(K=- z^Sn&$e-DE~4@JaXd?9rBfsW18Zu?eDS30}ezK%H*&K&A_mf7CL)8(tYMeu1Y*d6FR z+{zycQH5=$fyv+CEEX0N4D(dmPCEjfzl#pv*4NNswNjl$mcT7dB zFsIPG2elj3PYH<#Kxm1r^V?4+w2nZEd`C?c?QLo12T6COCk$FQWE6b7`T`Vb6)KTQ zdzvpa2OlC_31X8J^^)He<5xIScH+7$dO%l=ibqse>` zo_n~MqgKl)fik;052(t~Hh%9wA_{xA5+wOd*q@YCb;i6fj+?n3E5!x-+g?`<;7V8L zpnKz!sCGy`)R&(7zS2ns#cFd~ZD}Yer(m9C7Fb`(9n9@2IB2Kb9bV0FvAdM$4eQVR zYTEC`@nN_ef+T3={8nmvIDIUla25Oqf~)ooU(A_N^XTdou{C{6m*GD=E5Y*LU$D>J zaTKMj?P{!+WuP4OszgD?5^qM*^=X#tZL8vKm(nv!S26S!T7L#QKZ5}2EYa}kM`Lb_ zfz>1Pc#{8_g5R01nXjz6Tcv+?dgp<*zq8W4;moJ4i3z;^hGqILGWMayFab&9cgxFb9`|-02(M70uvHHtOh&B@UzJ$`yEbx7y^KcJ4(rlhu z^Pis{cAIK~-)|dft!1-|rf^nx7JzM<*|UZkN;|oZO?+bL0*d++n|<9{A)T~|we_Ia zbw2=gs|8Lt*$ZcB%!;Ew9&Qu8iE7yHJ%u2B$rvW{$DU9?Ph#b<2%_g>zp0SD3fiJ_ z=+1>EFc9W9vEc@9NoAOy;D%RuORB^8Ji7|MO3L9{qFvGI`QV@1e#C0172hZARC^>< zC{P@f@S{p%DTE+aA`p>*h}ECle~0oP_%q?wB6*C5V*tiOWIRO1L!?|p%0(RVuh*ve zohR-2<&*YrhqwLP;fKfbS^jPQpB?TP)1gZKy6yp(qkgQN#_B)5GiD`sy=7Ir=S5`ot$}D^gS%?g@b=Yo8>$D1_~a2 zjv&;@a_X#P(IynVJviB*Y7{Yg9l}Acs;eBq3L5<`WX9mB7aGTZBl@UbUE|P`4|u0p z?&uw`MZTzTs*8<&gm7@jAwGO>upHM(T!lmWH#aVCsc#A4Y8_9hhga{w4*#24L!Qgw zxroar|4+}}{}qngpL6Z%e#|uNhjV^D!`H6z;jka}^h#~A?qm9Bj1ihcC_eoTUZm-d z&p7S%m^xR=I=W1LW;F=lM-fM_sc@7uRyGWWS8eodx8Y1rPNQm(w0=7Y`Cq1`ZM7 zKL>@M_zS@o1s7tX!8MM0U?R%G?L;Ja4H5odBBBufZ^3V(&?lmxewPUQhXsEo_#!X? Ye(yvECE{a=Jw*6>6-fI$@Fe|z0Uv;4!vFvP literal 0 HcmV?d00001 diff --git a/moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux64.a b/moveit_planners/trajopt/trajopt_sco/3rdpartylib/bpmpd_linux64.a new file mode 100644 index 0000000000000000000000000000000000000000..8c3924888764137d5623ec88e3f6423e22f23093 GIT binary patch literal 740972 zcmeFadwf;ZnK!;eju0{B1Wh&Vr1jJuZB)brqb8DS4xA%9dV+{hLW@W|Nl0pL=Av;1 zLoA79cjo}D*wPk9=Kaz4r5$|Bv^ax`8bC<^FNin1U}@D3sn#NO6tCy^{XT20lg)$$CG-Pis~S#?{Y{_^n`hK{|8iV91MFD@=Eo)QWb$}8`0 zC{$c@=_M+~qVbkxy=_@JtJVMc1C}){YFSIRSk~$}$Ns-pZe^U-Xl0akSsA@$R>rz@ zR>s!1kNw}1Wo5jWYh@hDvBm^9T4PQ>r2gl8VvV_d!^r>tid$p;`LH$S&?GDKlr2`K z9k()Xt3UStlSx+K)a6#7Fl+^qL+byhPgsHf`~QDs@E2@g?D>nVu?uQO{(rd28q5E` zUvG_lX|FZ*lLhiW?!p0U+`QG+xMj1{|Bkn{9YLb=pn+;ahr{VwO|H(DWt&^KJS||Tvoptilo2`@I+F+gh-gD{y@fRMp(*IQf zYy3i6{eSSBH6H(`6fU~4^@i%YnuhAdmfYdCP3{&iZmSj8jm`Xq$FAzYi?{5SW9Djvyhu;X}+blt%JaZ=7x^;7I|OS zo~UlDC9u7tHKAT7aNF2SSX*rk?)BU1W=R3WZ7sJFR@0fNucZKPsBLU$YLFC7b=8TE zmNubQ-!npW=i<5!kzb;{Rr7)yCEL!$H>!7a%{8qJw=jO9p`)!kfy`#1!+R)x!o9Jk0 zX`VhEudZyXJtpdmtLp&4i|O^%&5LWNTsgC|>Bd@UZ1FX1HMMPcF$)hJa~hgz+uHF2 zTrJHtygP9w#MIK%+E&}%Zb-eZwqtIqc_4RbWIE63={%A8y4J>q4vB3DfN;{ciZKXn zT7%}Qva_+Hp%q48D2mlA9(gO|G`DxObtXD08=9xLz=*D^ZLMyrhMMv6O6Z65wlvo^ zcaWu8|JD{Grt+HMmfnp!(MYLAP6nAJ_p zcX~^8TYGIYBj9OvZCyiiIyL|lo0o1rGj2MkWAjLZJ@~a0yjWmex3<$}MtG*KMi>WH z#DPOlH!89=7-gfgYTKH?7~W57t|3L!svE1D#R`$Kx~aMguV!7_S=(7ln$r(6YC9@D z?`W3kchTC$T0yDO&26oLeW%}6G`G_cKvlKPwQbdn$7VXctrn4$G>y%P0UisQT^p(S zc4vD>T0!mAU9F-hfBKm%mDTMxA-m%+-!StV^U`pWS6y0^wQX&+UBYo?bw{H9hS`;f ztZuKfVGi7M9y0Y>H@=kkK_5%D$VzX=0Dua`NZ)~f< zyODBu^{rxMBY-J*{f(B!5dfZ*ejENa?Q$yGr?)gW!*%_J#;NE=si*6ovOfVQ*(9>3FkS zZjD}fofk5_rBOi|s0Sta26#bp3w_*D-6&7Wjn5;MqL~;sQK$9^)4gzn#8;71@LFQM(=qs98 z@f}w+od`x$Dq>}Ad;OGS>J$%rq<%X#{s^3i=80E~+)~}ph^M+^oTPrzUXYGU6-Z?X zColx1JvhAUP?&&DJzrN#VO!~!U{@%rP26PHR#V9hBM!jh3slKQolc=QXa}oZttsgu zTfU|TmO=`MgoM;k--&wEH`0J;Fs3--DcYM`+L|bb_L>&SroFZ0Rz5ejES4tX;@ak> zx|SQ7rTM2Gq}@}0Q?qJ0HYE~h1Q3P*Ww5J7-vH9=X=LepMr>)TNpwg9iL};8AUJi-E1blwtArkJlCjZ zXM0Cub(1gyLq@wo39Pdf+EK0L&el%V)^5M8sZLRQbE{P4%n~ANZBt^rtqF=ItiH8f zwXbnQj|fl)8-=`Kt5_kHJA!U)@1P^Y-QsHKNAz@STSHT8yJc0^)wQEPGPy+$N|>>T zDVK&q7Z+ZPVF&eFR9JY)CB>o8B_*Zlv52Ly_?2TaGB6~et_z_x^X6BYuYME(qrY`%W8US#`mAyQ1#3fv7t_94mc!>E|mF+asy%6^TF(9*;zV z6SKEVgG-(5dWg2Q!&6m=hj*Bsl+#Bf*7l6 zi$CLO!C~f8oY8&1y=+N1&kFW_1xzEGdwWzU(y0s1-2*!EKt~Db$g8VcH5%`^h*Zo- z;gJ{~n)1hzkXP_CF+ZdGRbb6Qg2H3C19rhrw*J7Mk0@f^{LaH*FlQ2kM)rd9|A_xx zV0Pgj`ST&LSN(}>zR7&T8Qs4^KKbso<&n~TOTR?)#D7Gzki7}Oiow7xs;7I{y(arX znn~&IrFnMZBg*q%GfQ_vN;$cuM}iY`r*s-ud zd)x0ar*?)Zs)=AA`?T&Cqi$tZ)DhK2r&bm$jp5}5jH@t!_{UF-r2r9gC(??dpSKXq zhwvBdrC3hu-T|!HBUmQ|SN;GP4dzt}HRX62HFPr+2#=rO6v``fX6HbTn5*i@04`eW~s#5x4LGWNSr}*%RW4Z7fLJNN6j7 zr5{pFxjT-`fS1_T{i-rYcW#c+iz-lOBe|8ffz@IIWTy})DiR-7!lWX}+cK10SD@ZR zNj!38FeiV^Rmtp3WKs16TKlVj%|{&rqxeGiCYWiS*G$h+h15>GtIE3Z10Ewip6Q5d zXZP*uE|F>>tuA+~*g!n78w~)ItpkEQI3y?^lvKT_mS#pv^L4-5u6o12_{Q)KM2Fven z=nURLiT)Vy`R73_^Z%8F`Awvl7#`RCJ$G)lA+B)gt*Q)@hR6ByB#EG<|3xASk4%^L z%QQIYOeT8{*(`hv&;`ZgnB#LKY>0%h8l69$KXl6P9+?J@GOpWE21c1hAuJZJ0o+s6 zRn-01*yz-`#mwZJUHF}t7hL%(MhMQ^2R9(qF(j%hLsPsGPdjKu6!)j3 zsGFMc_n8&RB^T2X=1eLCuAHw?PISog^&N!uRlp{G6{rIj)dery-hL5ogCyru8VgAz zEk{}1leMSeW28<2+ZSfFp9I*%tZ4G8j1fyL4z9Rfyl4|DOsROIQ=8!O|Ha3KHdhn_ zrG;(I?rTu5D;~5gD&P*UPL`bxVdfOGrn~~4?=$?XFcPeqN(!b@OMx>GYeC>NvH>bZ z6eH|B>19V+FJx!eiP%a0tuBeEQi3byvQ`yjeFL4rEf9#uXB-Khw;u-h7IB?_BzW!f zq~m=&?OWGJ7DTR(ER5W+1C)y-h8xgg!Yh6CsPOO=I(+olXR9Yy0jvxwqbnzS zT-GXPk1JpQ%L9I{9;5Ce6LOaEwoLyksAXMnvbvi#A!p^7*o3?lnXw6>WFR)7ATpsa zGNEMIxI4%8pLErP9*xJEF@5@Fp@JDR=bjt7X!4ZF7lo!27G6|%ap9Cu!R*?akX_vo ziZ?WOcB!`)6i+$VvL>S!)lq#T!j3i-)|Y*kDqxN{OUoh}=A$32JoVZ-N5iG?YZ!w8U%uv*Kd(u6L7bzd z51E8IH2E8F5pGDACf9(|`4^-i>c*ru;dFqR-k6Jten`{bWdJ%f=?wUC-1vFoyMZsN z7=TgZ?Gua`!sS-TD{lxc<{sc-lQ+~Mm|B@iGcZK&m^mL{&jrt zT>iXHBs)eg*M^p(1xs|N;or|ci}Q){pQROg1KxWtfBxQg-h0LiSnqmV)X3Y+6H1J9 zoQM*_Po!bO#hZ>G#+@oBBk|20*~tJN^K8P?HQdO>z-c~=Z_2BA{}l~4_G91xgC4&Z zAe3-#ECnl&;H2Z;h;s*DCSMiXvZm`$hpowx@a!TqTo zy_kC7Y7L*I?a285xq$m=6m(`VDq&%us(Esu)iAlpx@qzh3qy)UlP_X0Wpc4KIX-;~ ze=g!r5q|`BF-N#gG|{f7fUT<}6Xh>Hhx<=Zsq&ibflu(jf9!#K44of%;NE;s(M5}|z3|de z;8%O#Ui`B?a4(+DQQ&{)gCl#nUh~0?eEu*B{NqvJr|N`$zRvW(z4U+01E=pba+~6T z^Hx7vGe?1UjRJQ(aBsff_rSgRuJOQms~@d_QQ&)ga1kbc!rB%3AxA*c+B&BaD(SDAKduAy*@Z~!0R&&r+hw-f0J*v zuKbPM4E&ouIC1bw_~3?~Ru9~(-&;L!#x?QRi~`>?3jD=U;J+UQo}mTk=PTxe3sd-+ z>4O_OZ}7mq_Pp2w_ww83fqVJAYZUlTd~ie0TRym<=lxOOdAdq7{F?Y@`rrnClMjAW zRU@f2KDfd2fCuj7ce@Af<@Y5Y+}PD`d~ie0>nKN>13@^&KWO81G^N{?vgKF5d}2PbU-zWsK))Aq6+r@ zQjlR_6;C$CDi7k>POc6|8Dh-lkc9o=D!w;EpO}JSpCXR6@YP`w!mOzt8}YXg4n8-?dkiXT680jDJDB|eoTIO67=jcI zV+bkoesy@2yzdV$N66Ws9(k5Q=LO+b+nK{b<~T=pqa59B@_ zisUUAVA~qb67n#b3-lZi#yB)+;{#|OkUTLRNLj7J!!^mk_c)$QeQ_wefCJTq%oM7{ zz;ryR6k#X(MNM(%NZk2AMwV?S5IzK2g(>PI=3Z~b`d$h4oeje`8m8ueJJ@>_+Jb9f+1b8%>sHKoaFlxN;w`MVuWRO08Q(T19|~XRk`;-p%YQ zo#!LV$|k0Q{Xdd?H>>$JU?tb_WbWxvH#;Zdj*mHGqNTf>rdp)}mq#(_ zm)aG>oMMrT^~Mt~q;|#=f8v;2?sL;zAWID@wD$?x+_$@5(X2rVsU6@pxZ)gmat_fI zBCpEC?&;2w<$;*HFc%u53?NkJHRmPRP#Kl_aliEg>^FN8Y(TALx?h*b z;BM);%;2a*dzJ<;fLjc0j!Es9?gnzEIf2uW3=z9uj6nOCbSO(FodSKY4G$rKo!Eh? z<}opMQf930kKL!rP%_|yfid_c>mthTr)lLSQUt&i!pdZGD@$P(qOtVR0idu_tQEjwd5?2ZJjht@6oEVd>1BAj2NsP7PHREtAm_=I~-Y+jVYFDXe)sV7^ z&TIo;I@vNGrrgq;@GSbK68feBdZKbh(Vl62t5MyR_O~%XG<}qf)lSX+f9;fU=5~z#!Pp! z$INiE$I(+gz4T1D63UrMNDaTY01FYslCd%tb7~2oxb;jD^>s%byWbI6^WN& z7AzmmwusyD(?G<%E|7Yv^o3ymKOuT*m!0^Gj4&>2nGxMN4?~p0bT{EoQgo~LSrK=3 zfbJ#ycIgYZ?*)qu2vcPkPwaqu$S7WhNHI>ZlcCrm z1j=A@%!L+~R$8yH3E!-hX6nW4LR0|wZwN#)v!_JeiSUWB(&uBzNGj^Qv*aAifu)|R zOdO)mp7aEKHmif7Xz2?=Gzp&c_U$i|KbrYf$$;QToiir2WD%vS)UPU377+>_S&ogk z#gIa$!%l$N`Y)xtpYSfjvs31^C#X~_vWO;CU0Kcl% zj7uPAXF(DbU=Ame%AT0+rpJxNu9q{H~iqNL4on_lmt~3b-#dmJ?ea+BJpPw>xyl!k0ITRn%Z$qa?Y0| z#X+Xbgx!I9Ok`T=|s*38I=AzC|VJb6{`HkF&)18ydKQ&Ui zFb}TV#_M4JJNRWSM1*eU&)F*v_EIFO2u)p>wKPP=sS2AFGS-ERam&W1o{l(W!3f@W zA2f~vB|o_G`-sR21OZh@f$3Tnrk#;m(%?63W74$ec-o%dVW#x*shw9P<7nhy;yUnl zJTY;4D)1vjjVHcIr-lKaE6=zqewC^)n3D?*T7@lkANoK3c3X%M56H0y;f z)(dD&F9@TWh=yk&$`iE7y^I1EPE}JE0yzX$Usd91K1wzSlR zX2)hn;`SqDd8;UyobcBka>sKHpVHJ#tXCO^r=Qn`ptS33Vw)ek_$0ivADP+G5vpx&>9ilXEmYUi7OGxsKgeBb+@fPY zw76c8VLSgqE^KEd^R%6NNrCPBs0zW(?~)0{F7?Q#K_Phfhafvt*U;E_K|^yWA)7mD zCR-saq`i=fctdLM7q*PlObS_NU)or6cDwoozR~8OIak4XXmbs5Kpq$7n5S`unG?;S zX%h+uT5Ws z6r@Ydfu)nD(_bMEP-; z*`zn{YXCE*ire(HW)%4u`b|X6!TMo*XVU*i=a`?+`PZ9_bm-6PM6zSlE>0-ps@DlP z7RZ4hKmUaJbq|nrP&of6uF9ZW-^tV~&|b{CnnlReVa}*o#A{-Z@uOjwzO$ zW24H`mq&pYi~=tl1ztJ|+|q-ivh70Mb2@fp&#m6r+s+-x9cojr>_$N(vo8Xut&lEg z49KGy+a2`G!LY0t_+@;+#klAJrLQY}aL(cLy4nXnSAnhB8qR!aiw6HUJ#g>b?Kk;= zi}Ag4z}r1=Z~OvXFEPFs{!gR8Lx{)AUw+h9@xOiyx~RBR4?_R-W6+D}^z~IPVL5m_ z#o`z=2cYM2=y^FPW2FuF!Pc;;IBLlSOPBNG^q?&32V(X9g4Jz+G5*hk|a z4;=xUn2Y3nzYI39sX0J6*5XUo3GvuY<2XsV#NR5TJMr{@w;CL^F(_0Z@iyyrWUsVO znSUPPpzko#gZ`ruZr0->>t*C-zPF#$rlFKZSqFNeC?FhAywpiJ=-;Z%~FFilEFtt76T;vJ2_{|C$gTC z=7QLw5}Kn>3udBjV62^~y1wb11J=^7+s;nx7xssMeNweHdb(4*N`c84Rg~JU z7f|N}SJX>?Orejt6EPIk9U`|X8w`X3Y21NO)Pi2cHXdjgBa5K@cX)|Gim|c2f$rPv zgt%~GP*$bN0C}Qr*vsC6a4@g}zv$I!kt*ApJ{b58!CG`mRNUW`7S$JIB<>21tb|K> zpMN>TmVa6IcWDKFi_GjB2(H)zgfN7&iP%VHt2nj;nRa5goeVt5SBR254!AIUdjK<3 zzj-%!=TWq>Fu0b~$z%u$ydn|e)r6}|(w7dB67KUFNqt~{aM`_*KG3goO>8IkQW#)5 z9Cr)$FGduWB`P2?7@&KzMiy0z`nKs!026{MzK)(Ly#&3 zji~|3oQA5(jJ*cNdIyc75HM`V(e{enDq}FhH&LxPkGi>fiw_14b-@X){5n!-tD+EC zUa*)PJBVJ6ID2WlOAc7m-LjwPO+CR2KMmelgEoWVMEl9aF75*e3{7_-Q!b1bmDJ(=w zB?$KJN7kwBQ^jMdQWsqD7|I-#LZzui=%pFKzPSQDkt)wXsSNgh1dfc8#i*U&k4&|? zFSShWo z#4|Jrj&K;q>E@qde1GZ7I#Fu;BJE}jsOadl;ng_ikCjd*=r~EVTR{!CPbw> z9^PgnZfR6GG?irW^L%AW8*QTp&lvE|u1My}W|LE~(dW5X-!6!HF1D^zJ&Ro%XFxWR zQRl@*blja1z6csza28%-+>j3RrGp0+gsWJr5nz|kg|7#{vkQIsm>d5brh<2Mp2c_P z(L~oFTi6b_^|HZLHr$J#gqAu69fT>+UOQ~@O*VL_sb;hGIEW*GF9>xoM(YK zeV_A1+DY!2pta!7B%3>&FMK!n-PO<&g!VgZ<$E1A_S^QavQ@eYXsPKn2xBfbHpYU# z44g~__I^f65M>Kqu|9ecm5S)4A{jr)dTHQ5#!I_iI{2G+S)be|ao1}!*{dPN?z0YH zdVh6zIg*1B7@UOXL7azJNlqGjAoHbx$brDvG@3hEaMcbSW(T!zLL!qb1jRj3ITP_? zREfH9*}I5CeUlaVhP&8wIOD*6T9f1r6UgIOc>cHpnPLyb!b(zArXc^$A0nyBm$IP# zQae?x6Pa2RTyZ7rUilMMK9czp`(EkBBqQvSjH9Yf?21rM)`R@fGZEOn8RnyX$6z^{ zz=z~sr@_GVawHuYm>yO!eb61!bHFPS-Xt~Cxx-bkGxE1S&0let3>J?YW;IN)Yu1A~ zUng3KzYt>QPTryenZxVA4kM`*F%+q?9o%G~ILzBdWP!17Jx8gMYBG8dVPq>(qQ+32 z4~mLb%+g0i&!Q-hGu=3BQc7aP%_Ijb)uwQ!1|kmH(em0}!z`-sHtOVlH+ud#o;Di$ zfnH z!{xl;^hJrDM_9nQ?MCn1w)XwnpHcQ%f?cgEFgE)cTZAy~`T1p#$``;g{`DyaF!@~U zE7P*ZQ}*S5_GmnLl- zY*JsKEM!`6Vf+9UE|1u(kG+V-@l?GArRU*Uu)xC<1(*H!L-3c_3Aghhq_Ut4cNcyf zyz@H*gN-%F+E@<#)wWdNPG(Po(4I2!6!xelNn+H^&$`OAh|vPd9jEJiOu>!l71q39 zJ3ZbG)#3|&_f8-~w$HTFNh+&D*6So|H90pk8IZLW#^UJL)%2pNMr3}GmQq4WI7d~$ z4aMX^S)OtPG|4RS0JNiWnVF(lg*aQ4Co@yx1k!zrI9F>Z=bJ8um_DCTntKQL{ATaG z{VH8jRC&R13#O_rQm%*;($0xyh_uOm--o6zE4w4rk(azVqx1#k$hx0aD27kM>Pcf? zv=MUao`J5|8R$Ka9UO;8V9|n7!vi!JRhaZJ1o&oV@kCz4&0aOl$-XzPI#<|Yxg3qQ z9}nKjn6YRz z-R-yNB{Wx>wW*(sX?si>^Q>acG;U?haVJ;Jv#Qccm(fZL6oPSe@dQpUIQh!b?0cbu ziP^siCdsotjlr0;>GB0v4&bG-9C`w;X~SL3OysYEY5zFY@wL>p(r1)Vy7ww9Y~yR2 z6Q4HxbIgMNyDeR>!i1^r1tk=yvUIF(%>Mp#C;Kj4c&|>B-7y%D1xLpidJPQSPtWj~ zpoI0HvVJ&cT7M_H)#CMs*TK$V(c)A+=KuVkNx$h4N)I)R9x8eQXuq5d>a5`gM5$Xv zCbj*KICO64mNLRZ-h;?-oW@hnZe{k<_+8lXJXECpdT{B zp&TgtH|L|#_b$uAPK=A~1g4YmR*z7;^jm3Qqw|gSb@0NEg3G>xsHUn%^S%${q)Q2@ zUyf(cD-M7~mIljGP3MGW|3yr@j&aaN2{J(sUg%BXZeR-4L|bRopC=Bu!WlxroHwMb zUaVd9*=Xfh#%mm!a^T0*A4(5gWl-*M`C|MFxX3{Kxhyi!%X782ByGZgG@oA3j&J$l z6S}tR0jAF;Q!s3}Hnn6Yj4D~{Hd~^kJsZ)B(&6Ih+FmuTjooflQSV0Qc3}-GXsuT` zuqV=rg@1b~tyvr^fG(3(Eu!V5bqjZv7hJaRPt@&TWilYXj(skiWdghF(0wSSV$jqG z9V5*jg3Hch8fb#mx9QawS4d@2$y6kjN)3>AEP-MY>YHA0ysEXSVd@hLVz5lejQw|T zRkc!>=y=3S8n!sRENiqq=3zV8VUHECD)#ABH~NfT4}lil{GiOg&c_koVkcgpe#>6e z`n~v_6PDfa04u*hj>#TQ&S0&P{b!uXvYC>U;y%3QkIE2+5Cy|*8Ejz>uYMbn#Ne%n z1&wzolr62o;n{eBraNA(LwuANoGP?{<+T9q`uE?`yZ=L2b+&;;gHZwZizWOo? z3ob5}Wf$^mg)rOH9>P&=II6V%FT@qM_a2={#6y>pk8yp`Az1N zrPJl<@Ei?ihrxSgf6@Cia?duI_nL$U;`FD_(did>BkQz9`q%+`3-1ud}ccIHv43j_Q&ovz; zy@69cCtB;VN$0PyjQkqD4Wtn_ei+}G^#9Sd9&hOUJ55G9^yhUV*)i%tE0f{T=@-5m#{17)>%p}L-0yEL!x!z4aPw?J>ib0J z15iwa8+$PE!x|n!$jjt(KJFQx?|B*c6xw|($$YdG`aW$@gLd*YcT&=Gi- zhR^ZAdo;Yt2j}C7&V^9$u{!p#LFNfdEb-8qkG+=5WqWvjf zlO9ukXZYZzyw4p4zGM{m77eF=BYxut9`?ll3gBj~)MFkv;~P3(_rVQ4e;x&%%fz@0 zUnc%FKDfa@*9SLpxX}kU@f$~hFBt{C*#r0TyWIolt?}DW_~0QjgX;w!JgmUhun%tN zJVUyPBXThC$)mup7zN(ogPVMNJn($bV)S^Y2TsyVz7LNA|6~;S`P$VPJsLbyM}c4K zgPZ#0?|g7mzue`6n|k3NeDGOX&j09x8+z{d!A*U!-3K@E-}J$w8vnof;D(-D-KaBi z$ky?{=z|+PXZzsgI{pP7xL04-c;M8Rx#s)eru^3U;N?2OO+L7h|Nrp84gLS}37bgDV zQR3h2gByGJe@21d?}Hn=9q_>mv_NiC^r4 z8+~zo0x#n6+UG(K+-slpKDe=mb|1W)NOAqG4{qeY$p<&|d(YiqzU4%MYp*Z9f?C$g zKDeRhO&`2mCwSWjH}rh!gB!gBSdro~ayEL&_Q8#voauubJB<0@wnA%N?}2{_Fyqe? z9ysM-@c+~U_v-5j51jFHHU29+YoWb(=KA2}I)0-M9@X%*9=JE(2R(2v{X0Ey=4<$> z)r$7p+e#0d@xwabaWa%PB7Xxv!v~M*_~-cGCjKNJoILQFq2Ux?ojoglEIQeD#F#dUE=shL|Ze)6StFM!D6d&Z*TQ0&LIQi9PZ(Zbr z^Bu1%d~n0pH9okJ=MQ~w!`Fj8c%edX?eM`({1<)jVjcf2AKcLMd907*W$ef3{VX56 zL`AdC*KlJeM$R*R@lC#s8cunhjeo;$y9Z908TuU`+|YTi4{qe}GauaK`%52ulBWM( zMu8t31%Ai}H}y!ab|B=7^c(zFjsmY51-{S+H}pF`IP>7O(g!#3|JesO_PNgk_uBIj z51hD7{0zNU%M z_WYg?ZtVF}4fosgS2RL{$K-pthWqU~>VZ>chW`0JxPG*5@xhH8miXYsT5fmx;Kts5 zFbe#^QQ+HsaAVI;_~3D!?>-;g@b#GwZs;kLndy;w-@qfIz-Rd2#X8^FKDeP1pUjZU z*r%a$xerbq@LJ)68~peC;Mpp=^|S}>EiW&7;NJS;6Azqu8a!Eg{>RX1=*jiLwHU3C z2ky;xk_S#4rhI+R1NYMNpa;(Q#;%^$aKAkt@WGA$|D6wR%F7`iek0G!Gn4=gzftvQ z<@n%+-!E&pzuZmr#P`-0(>!qUW$<6^gB$$wd~jnwH9k0T@%pw8Zut7X4{r4P3lH3@ zujf2);x_Sr>w}wo-|@i>{U3YaUi?{FK}OET9+Ez|(fhA8+^_cseDRGuANRoxJums- zMn13m@asqGkPluWQnsx3HQcZFpq{TLUtYa`-UFx144q&0!3~`SK6qT`d#Mj@>>=ud z8@*iRgByP5```xutvVRS$Z5@Ty0T;Lgs5X<<<^-_6;4#jac1Rm z-ANaaJjfyHL7@jb6`#Wsf*J-`U8{n61UN)*9q{7Ll0kFlLwn7#kAhBr?;^m0E8mCc zz%fSUqv$cn#u!IB=*B4jwG)dV{iL?=CV|t z^AWySQ#`=9xOmS^pS-%C=Q5glFiufbA&eEh&$T&=`;iGR+`g@EV?}S+ zpop76sh6Y3!$XmY(H z2p2B%UmOoG2<1M~~s}Do0r|wgcMBwmv6D z-6@ATQSs{F85}67N}G}pi`-BDLe|tbvW`Xdxt8%{na=tnf7WF*hl<30Wc?~{tueM4SQb6qZhmh+om7 z0)du$eQxIUInm%Rcf^vLI7Jh6I`bmf`dpFtOvuECnJS!}_-+!`dJ6ysU*QY}d+8i) z?%a6@W<**)hK-`C?8ePnUC*-Vih{AGYGkzj8#yen)fV!2;BYxnm>F5S&+}^eFu0k{3;Jb8pWo+NTBL#kkjCBr_#~@pr&bvF(japa3FZ zkzJD^V$VOvgRv51dok`Jjo4xVjN-EB6m7xyGR`m)8pC-J=WwzO)Zv6R;++^ia|C12 zzP?=^gxy~!x`QL=up0*GZ0jKp|7z~E;|LO_-G%# zV2IDksmG`@v;^C$x5_~TQeM?w0904D^O>d&$t-N`Dg#0khaNlXuf&*|PZtkyfUUKiv@LZ+ayRm5yo0sq!gz&K1$GBWGa5!VXy(Z$! zxf4gaDmR0ynGaWiMhB0kwqZRkL`V=$bG^q(7GLJ__HRw>393FTSi|OQ@ka(bC-BQ1KAIc7&&p{a`~gJ~JKq3f-~oBxgZRwsU_u#pU$b z65LZIz`GYAI7BJAF$f*1w9{@FYNxNq!4{Bj)WH`SuSNT0wX{zbtyG;@hD54l(*;d)t;Ok3$;rm)T|@Wi7kX36`FdUp#B zQ3aeV9Th3{>P6-13<#RXVTuhQ{UfdEki&1=j4r)TQK6+c2~Jh)r%nk_yg1!nLxAmL=dIa|c)ZC0s8@bg*2qmBu4OHUSU0 z8IbqD%@FW40@p`x7vq7Oz4Cse+IWO~ zTbT~|)k}Ky1w?9Ri=@X9F!CN7{^UJ)7I?oLu|jRF!?QUmm-#N2XZRU}Tz8Kn2BX+9 zg%#ZOJO+0WX)PC=*wiB7`t&g_h4Kv9NvO|i#q#i3Ok@#=1^zfjum%U(g5&}~xL>PW z?;ccVX)>1(C7dN#)=RsW5W%l}olm2>|_zAdNE{i{fSUGAz0t8#Qc|CQgCOP~Aq|KGLcMt(*M z<>p3*qpd9u>9Ix@3|?%-(jZ{6am2+OuI+#zxy-p(=Gla>t7EQ7cp}dKX!;_g zW&Ts}@4Za^e!Ps!%Y^0nUQbc*m0X2-?$Vf*fgAo!I2$jBON+@wv&wb)sx(C1m~;kQ zi5tI6_|Dd2az@USKb!IHt@z1!1&IjH)ByIzCS&uto$-& z+$VJYohG3U{pn96J4PMS3OTA1&<#)qe*U>6<3#xn=s~(~;=T9s=kI;zy=T1t%(dmr z>pyc%GRI)KdNQQ$L1fzKKRjy1wE_?h4WV)@|Q6oOi7tfuP5#+HOt*H&9=)g>BR+H1LmN0o_C>fUPrvryp-(V)Uh=?M zqz&A=7T7DFmD(ASUoZR;O@tplV-&dSS*yiqSCj8gJ#a7nVGo?QCjOu4bZ{|WmIVV3 zGchj0z49;fz$qgWzsCdj#t$J5FUpa)%%z6$S}x>hJFoONi3(3VHb14fxbzZ<`PYxl zuVSImSGk1cu(52M2U*Fnc{vi&c0T2)kQ@wmZ^*+piDX0()VkN?9Qf`KQbpZ+bMYK? zf3ylu913P1hP|5&2ss2%4ju8^MFV&~cTY4Kz#dI(REMU|-EjbC`~iGmMtN!vdu9g# z|8~*4WEhTXg_Xw?d%P^xV<2nu?L9O;r5x2Q+u2n@*^4h zGxlWcz^EeoDG=p z6dvcwO_q^(^wTqM&%uBXIjaH>7}~Nkob9PWr|j?1!S8+z@*q0CFTs2EBI?O&@_HPC zjvk`$jqWZ(2WZeeVl)T+2|d!nvre3M*h^90+h8(|?XtO_qvA5zA_1)q4-lktVQ+)- zRvjAjqH?Gg=Ed!?L`0g2XqKeH7eFM$&RoLLkHLW#awK|Vd}3}kyX30`fW5-(w+%2pa@Zj0vgNE8lF5|9J#dywf(7c7 zjvPB#b{9FI9LP7iZcE7gpAOO9h>KK5TnhuO%MYSd*h!51fpB?`9l3oy;2oi~pK(OW zUhIIM+jYyy@Aoaoi;T|m^!QijS4b@hi@4MA0f_10;L1x-Yrw=P2VTgGw}3pSAkfI!E#4i_Fr)$=k+UlMDo%Z5-Fk!zk&3e14;TVqW(?ZSTh* z%ui)Sz7-YsHRsIKP(|ebeSITO%kG@3LL&ho_poE z4$`$>(yL>k;)zNWC*URzx&*Q~R>>z%;0x-nNltdbV>i!Mz!(kAGh)fX zKuwJrZW$83SF6$s`g7!2dnzej$h=j67-?XJ8BfPEF-J-eFqN~khj?tP6l#(w`j!xb zbP{bz*rp8X`2f1B1lYkdoZ{+>5;h^2sA6p(MIg%aOi;q(W^jfBLDXH$t(EE8-gBw` zeyMrJG&2DU%vE8Oz^7n zXDQb;K!Pa|87|{31WCNkyO<|%c3+by{?7D4d?$q!QDka79PZw&@ljEX$-=|XotdZK zxVM%#L#6L7t$|PY66m0BsO^%mrj5$mt>M8Df3_1*oTDQr*xI7!_-}5TY7IHXAez^w>hJu7)LNBoQ5%BW`F^%+VcRx~JoI zBP>!atiY!t#Q?bh5t}63s4X2|8PQzgSg{U%^kkI!78w^XA7*Uy%u*C$p~6>9^dKT> zrw?#TOScNY9i>rB8{(kV?rDZFvMl9{gpG*XTQMuYKQ|Zk_$lyctZE<#R7Yd`20F7N zgJb!`1T-Y&#W70K=3ZP|hh*qw%P1Pz@uC zw)22ZSB?cksU3*98&#w_hzcjpY-|5lshJqp?PI~}dnF=nKN5_-%zSzL$%SIz!S7~F zvaApGI}*>mo5Ssx$rhe*gP9s6KYO-CZ>|$Dd zmW#*;4~jgukHx(Y+%4oltU6#VO>J;RHd%L+#Q^b@I>0%b!m6JZwOru6 zs#Kb)1{SA^g0d5SM+d$XM@os+!o!0GuEJSPTExf0qRPcawP^#h6c%6-(}yABWV5x} z{;}eOk>P8rSU6@04I5SWfZmye4S-NKwcwKB=GoZ97=MSVNoJ`-TUa{0r9n!P`nDad zUK(QvSu4`NgO&l_0{I51CQhv@lhr8V~eSUrK z&!gFjfs4ho8Z>Fev1KCyLN5dHY{6$)hp#Y>o~}`Z4!Lfka!>+k^1KE)&}R-?@0FAG z1<)IQ0#eeq&*@v7S{lycBrd&j#O*AOIlDPs=j@J@zKiMSrL%E(%`VhE%vl@@TT5_$ zlnG=*c}T4jE#2nqu1ri?D^v8t_?@5o4$cVL-Tk=6p0;$#mc&QhtFlej?%x*1oIR5B zP^9!j=d-1ArQDDyR3EH3C3nmmtJP1;oH~mqCM}bB`(fvq(svQn8Die~%zIDwpg(UT zK$*CYI?v#w-f&*@+`afLU^tiEM9Lw0?tZk-uQ?nm#X_vTX!=lEOJxFB5kX5(5PWx;MN!5!uorhoaf>o&ck(55;?45dDarghy+3FT! z)V(^}{kuX)LByd{6UBE?YesbNf}jx{U;<4j2&}g8#Z)v}pJnzn&s*((!y@ zj|T&?^uT!+DWoOR{glRG43=tR>(cwm0xq+TRCzzxNfU!V!cbbX5SP)>mC)N<%74aKK_t zzhNT-PwP;BM-vewB6?J7NFB;Ljmijy?bHyBM%o1k=_%QQMOQLcTo4@~i%_0~%01Ed z!R?{9k2b6FPar_y#SAG?B+&$w{7eg4@gh8|7Y9lmF;_NgOX#WLP1(K2hXe@Kw2)JA zmY_+-0cd_?SM?|4a7*b9*Kqc-5$zSUnwKMIA&Vk3WYG?^2-R3me>f!B!!;l8e?6@i zCL~!x2C#Q|2><9#y8P`sCu${r`LHgLzM1|nJL1pLM5sZbbaK_g3sVz%|n%v2_PmOUMVT{ zhf7eSkd;E#EMWIA*~R$DAqm&Y2o|k{rHI25ELb!Rs*U3;HlEoo%3vqpWcC!x#o!@l z(TmOjJV}*f~8H^|}M9;O5(nq=ihA;?Lv@H4-(xXpNu$R;LAxW&d_{eVlYGHtP zy~4Y!8YC&PVAV7H*~Y<(5)uoOD3ox$%*-PVT9{;?cRDr5%VQ33x@`B2EU&;fUq}{u z3`ZeqcBl^{WQUpteEhdnR0o=D4as}78zerysLl`t;}F8> z)TLBNh_tgCAn=W1#-wwT;8W&I1uEl(_XV8dV<}}mbPTlgR%R|G3cy2r2_n}qGLWg> zyJ?+m)UC7raF4u?hr6iy98w5Jl}(BeW=V)+N(GKDI?6K|1`=*mUw=X4YY|<@EPaga z9DX1jXF1ZN*t!^^$3|BLFC!--)}&8Hq@M#TN67**+#raJ!qH-uj5n*#=b*GYxnWAI z9^kZlVOl$}RR(3ZaH`5qY?g7`cmgIygo%D>3h{fOd!g%!#A(4t`ei5>B?~?fad5L< znHfmO@rLNZhyew2a1tSjaByli8}<|hZqVJsjauxg+vPGkAXLGxNa)5IIqr8JX3eAS zeKb)X?Y?|7X2WO)R8iEui0%Bo>44D&*ioZSMU4A{iq#uvKh; zXU7xoA_`O6FHNF~&j_U=K`}f?l_RfJ6ddeIim_+lNY!Vnr9O+IJg|>U=XqG$=NiGU z7WCLiHz4@biel1E_silw1UO5!lna=m*fUIV1LGrHCn2m!LUp=4%iVH$R;EcmjX@%I z5ZK74i7g^esyE*+Z6THoRsp6CA+2<~tZJ3>Lm354l#Mt+SYkN^qDIDa!$Z}>8&#=Q zy^1-sT3D#*n=qqwB1}DulrEIAQfOqzu8@*t?TkJQP2LvcXKw^mY$J_7UAy%P6R|EG zcC6c7+9ZXLiH;i|lj#)GS-{i~=&DQ<|Ah5y;9X6Lvzrxe;5{!ze}Nua5T)tPL!V)H z=DghKx!e2p!L->y2(GvdJI;ijRy?}0z8wNR?|10(M}iA+mMZ%Enm>#PfadO#mmLfQ z`+`VEBNi!|0*J!RC{!FqAaF<13sJ)LTH&;D8p04Ij_4e?S0hA@nyXOts_EORmLj|J zhd~}Fy5UVWcz_irgkHa1uX+?~#9R$@uwE@xqXQIMaye-eTrmg3FLW0a1lG!iN7_Ff z;V>IO!Ifb|fgog)#1Lr(bKtB|+n+ExM7dSoFryD|$whj&R}M23 z{1(OFAX18el{I6!0=^2^uTJE;_;gHWWis~+Qac`}re^bQ;&_}R{jRoNXDGO0BF0hP)Sw+20ttT4%WdsxXxWBT4UxZVD*E0dokt@SNsbm&{>Qq7?wI!jhQL~ zr%6lkLR&+Wh*qpTqp2XzoAuz=0uE7Oh?ey;>JJPzaY?Ca=ja(mv~D=fsA?BIe*teV zbB)Y+lOR<6Mp{iPGvd&bu2oQ5gjh#l=oS-_Oi{%Y$Rn#Vng0WJ&RE6K9k3=+)jSrC zD#z~~pF%7OilvvQ(m^cr6%flspG!|iX&a)!TbQ)FSdOV<7lx#XtkyXAg3`fE8D(MH zzgSkW7mss>x?j;2PTDCqLzl3lswAN*iWU3Z>jc>;CYivN1Xyq^jEoHXQ4!2s6rpNh zwi}T`Re7jmbXEflDHjS!i;?YvknIFaJ*X$v(1xPzNSg|}BmTV_3$ZCR0*lIATLBta zLl77nuT`YDUQ%pTJ$wq6DUoQuV9=&v*b!o32`~{%N;Bg{Ob+eBKsu;ma7EO|jO^z~ z9BD@wNv$@lk;`()3N!1pFBlo@iX7*qIaU+qMt)QX2_cnaEp1KUh601nQDRYq5mTDTU z5e~sIHSN4Z38QnbmMRp=JJrfnB?V5BS-U|_%}_98lZAW0U_@U`KqI!fPOzx9wG>ZM zQYDf6s~}dZdY$b&BHzGBYF1_e_0ArTY5q|vMWcGCz8eSPmSx4Gc zP`fO+#BT$?@TD3c=y0s~BZ@Q|8oh7e#;>1+9C zKA?O%=+IJ4#puv-hET|1fJvhh@K9;=x)a zJsMY(8hSJPMS9wGo9YF{YOla`*+o9}Opo|S0q2OtUg(XDvV#)Bhft3g!C;e;t-28D zMwln`pna{=ts@*YVGh%wSC%EA8oiL^Qj7=Lv9}dRsCrv!0Dye4m&L)GRr22Svet%s z1ipkFtR?Jf%|R~;r<0 zD{pAd@_^2l3^kxmO}j|6NFFA;s_~-)57H=DAm_{rV!#P$O;7{ml!DfV!ooyDBh?!a zqFr{w(MZP0Bx*UIIRZz-Ky=@7N)`n5NCGpm3(W)0{;#qiv?=7h>JHFSR61x5aE``2 zA(~z<7Kv^Y+?(lpZ?@KkSlFu5hX5ahj2_|N~v(GZj{uZ@`J=$HDk0PYO_Sd25wj>Dht4% zGqqdb87G1x&XR=d#gtgj!%Fm6u~EKiHc3xN>!11-`=kDKC5go#G_sHymv+LcZ2;XQ z^C(l0DAR3F>QTwjFssZPuPORS#@|qjv^nX~(JWHqj8RL|mLOogJ0w_5$4;3D84r9I04E`nkbX5rB`fg>qs%p5t`q=1x}t`n{95G8@OtgsCYNKuD72+>S1pf4>#cvBJJ zh*5}eL9nu_GHED_P}6kETuC{pglEA(4DB3^DYHCsr1sqVW-2AM=OAv-z^EJSD+lEv zRm(!n$W`fEIcb@Xr(>vxtgs{p8VGVACIm4v9?lP|z;byc6 za=bc0Qql(;Xn+2DlCn6H8A-|7|1V|A&h;tB5)ILy`Hyszh9JV=SaA5fm+{FKyt}Ul zQU`94BRjzd(4e^Gz)ZHx>};xSYe-aAJlGhjX{f7fNDTJP0$QU zbGMBEO5+quZTrqXS>A7?MkjL!^bd~ZAog&P-Y>gOEL}}2q*LIk zokMrSCN8ZV-H2UIEOvql7TCl^2>p9W z5DKa!%A%Z@$_1m60&`HTE0$?qAR&)5=A;+!4PSt-L!}EFmW@4wA~^q9_Ab;|Q}8=O z_!JV$r7WUE)X#%kixFPFB@310-9vaxskQ$Y|LBLEoz(F;J*;*9@b^^eYhSO}GPAb2 zE!5J{TJdm419tO-ZtR3}nEyn@Lmi>^#+F+{3H!m8W^C12T-yxCO+>tqMJ05s3-*01 z*m36`mU!E_y9&WzA01z!b}|6U_rG^JasxD7yLm97(%cYE}@j+WL|?EbeO2~BTn=zx<#4ANPB8TR>; zZrgd7?rCS=Z2U?oBPFci4+EfV@~8L+C#&b9P$dZ8DBUZe5l`!-M!}7$dt?$0Pbig0 zj~g{>R*}f%6q=ejGyEzdP38FeH&Usd&Ecg;)`Rf742QP?=;fdCY(!RZ=RWE*?j)&HD7s#P`&-o$YmLD^ayzZMtrha^$8B}n&b}20wE`cw zKwl~%A9TbEF2K19D%+&WQ=h_+WS)4(JP|NY1k4iw^F+{tK<8uZY&d!V5_`1e#&1ui zKx~Mmq5~3uSY}ObP@;Mmk5N8A1ai%tT=9TSCS}2XAQbIHnP|DOVvE8CEY8D< zgnJat`jCkGW`UBpbN}&j(!`>$kXXh3^p++gr^d;C`e(jMV^iZYSpCB@maO4lqaJ2| zUD~I3Nx#W{GDkM)oo8uhw1#l>f2E&{_!|V?uST2Du;c)-@np1U@uKKaNq-v7iB6F< zW0&C3{cGgcBXI47QR5tyvZ7`^N$h^sT!0@2ob>FKnoKq1*khxyvLAj>Li7?P#AqZ! z_Unfv#Qc?n>O%~YCw8_(^OZ^S&u&$cMksOj7O?Cvzke@FGy#P z$wLsGdy79n}LS}j?U3I>E76f|H2A?t^7 z)RFtxbPpRJ&i>&ecmR7G0K$AhZ~ap^{=mI2 zr0wbud4ZiNyHR#W``IM$wQAf5glrL>(KkRX%nr)+t+Z*J2sDNQ9Kd}= z#;111XB8PA&rAlsW@kdR08;c_Y_+JS0viU4q^TgS1J=(r^;FJky@Ynr!$iQooYNbo0_eU&jf9s=8Z+puM^{0U4C<`nOWKQP>Kubo zfV!7KX??v=8oBEd^dqfe(ncEV1#a4Krse7xCT`UU6%$KHm#Vd+?#~LLIv&Wk{3b?9 zN}W%Yv6@7Uc7G1uW1^$)eKZQtK*tlH_hm^q@jkxASK;v+b(@O00%XMnNJwF*Rxf;p z7_};cENM!jiW_pZSGYhmD@3X(D%!|$+6e4Gwe`^w#4}Z<%PwS&)_sr5%+*U2Zi4RkB!P*jauaxpVGNdNGt>;5@HCS&0;uM3Wo$j zIMN(O*GO!fR*2@X_WWRK7I}nl*c{%R9taiYF&ZaA0UC6l)+;A~2iPcT9LW$%{TMD4#j>0ZV8+GResXJ!}b%K#%4P38ga0iLPVX zW{fSV>XB%2Xb3bUvb;`G(ffmB@-O{In9;8c_tJ4fCh6WI9SiG$LtxYzegT}5QdJvl z*4;(picFVitF{5{hfv^XBcdv?iDNAQM3$3R)I79-v_a4oKnbRCxyMbZnT=x_0%_PJ z^v7A1b--&wC3ER+lm3Wa(g~o%=PyfJ9Y~yijIJXQd3buEDiRQtaV{ZPK$hptP zGG3jEGt-jSXT*Xt-{N|on=JzQG~STS<_V{ zo~TGX&wB4Lo>b?Blu9hq*f&@dQ2W<(f5kZ5;h*FC?x~@U91r`$J9fgRlw2ss9tX^W4gr&=qR2A8e~Z z_o#U>iXq0ukQLiiM-dJ$*`dy1;{14IuAPho9?e2dkvVhY&XYKW_Sv{Ag9NDLR;it# z_OgLM>gn5#L>?0LjTOC>4la#G9)`2Wtk$3?XIWWBDk!7Tkp~6ivX3!M|0!ZrB=*_K z!1vvp)NTh`#kWVCvL1JAYOr*$d%GZ;I+e&cR+J2sU=D6s*&RT|1^IG8{gJ}Xcod`o7_@g{QaTHUweIBbF+6@3WpFVue-vRd6&8;(8Ke*rF| z4?#LZ{V`mcc>OuJOvMhv9;)StLq_($h#t@+fqDt`|5R>k!|~_(H{(+3=TaIYs7t<& z+POHM!cZ+`P zC;Q*f`a)ejN2AWan?v&vsY_urViy*`J77ma1U+?r78=gw^@&$tZgcp|-u%MUGMGjj zlRR?Z$r(M>#|~Uq0sh63Pj{D+Wb9QrCzb#8I^ow11J@l*6{wuO=nk>+oXqbLCie|& zseHHVSsF5Ai~2ULHrB7oO4VjTxK2*ZF*#TMy!*IKXsXh-u0Nt~TkI#SamM+1*BiDO z%z&B2W%FAXcYYy~Xv5K!GT{)J)ppH-Wpb4Eq}G;D9p+u;cP_qq0glmLxOnM;B{a>b zVImz15}|YIF1mR3Inf!jFSsZ&yRM-Yrv>8}?lK&axo})Z=$yq%@fCh?=Ysau1xv5& zT-2dYCodRRHg&?}1tEUK%cr`0&Es!cC_4S(3+m_0u7#P$g$w3)a5BJt*4xC(5RsWw zOsF&oV0wh)gG@iE>sTyhY*{@2$`0DVyaE<{J|8KY78zHL$dSnT3$8S!^+HTSX&J=Q zBZ0?NPM8FC4e~TglXGNT#e_0s9XUM`Td=fa0i>k0V**l|YBIa5xPCnDD&+2**0%Nz z+@a!27n*$R|4QQ@IQwh2(LI>9ji;duzQf|78sIgresPt(FRHO7t}vV!wjwuYWcDWZ zr*JT@A?LKo4gU6@Wv*~OyV%f6pU}SMaC0zwY;?uBqwg5mBl`}``7*RCrjDjK=@5VB z=z{3z$eOJ6BYKC&Mi=+6*O&7{*Ym=y^d?8CYGH_ju-ptSo82if@B zbdd?rXKfrEg@d9o9)p+^Z;32;BUB`N6nj9v%?$3=MWaCfcC#<|_+Ip*g z4Ic1%k_NE;T`_aLzN2{gn%!~K89 zMxb(Ka6yK$`DaX_9V#)jTSiIpQ!>X|jSS@uPTKY#Bh&qeK9&V{q!UrV`kxVhWT@D~ zPqBEZhqGTHJry2q+WAO%VS0}s2cvvQ;=48u)9*`!B!0lYKlMFWZ}CkvCMkX2U1IT? z=?3pJUT7YCpErE;xd6N)0KYx}Ul)LXB>=xA0RLtHepdkg!vOq|0Q~U)e0Ko;LID1& z0Q|QB_`v{tI2!O!^)e~||5N~eVgOzefKLs;YXb1|0`S=Z_}l=TlRQI}w<7@W4#2+@ zfYUs}Q0ady0H@9Tp~C-b01j)LFwi+cOm>#iZs(-5@y>EyP2t~E{++?UvNHLvq>;|{ zMe{q#XyKEFJeRb!2(}y=0Q1vVSIN`P*7-}W;1yH{V9XO23p*0?Tg3+G!iDn_ooxbk zEN@@h*0Lbf+ID5Aqa9OBoeLQ@Z3}eq(#4$}ZLP$vTC%)#1uqf|C&3ae%k^qGR`Lzj z-h%aAhU@5TPb}-?)z$NtEnF;dk>7IICS@x8gyF?fLygI|t)+dLSR=iveZjIN%O!Tl z7nUqc$W@}fr9EL{x3?tB6>^!sR0v$QpanOQ_R80ZlLTZPX_n$3I8or#3Mo1mNgl16>*ytp$tI46=ql#=gWE zo?{!ur#kqt4t|bAvW`JEkL6X%#&@yG0|khq)9M*AWpUg(6+GcV9X z%6q$myXD>Q;BI-{bE5gyQhLrM5pc|xLwCj9^PoAFSNuCpc-QvmuN>U9E&G9k^Ifg! zjI^&#=F4`gc#ea+;jgkdle0rKTwz<8hnw+0D0ID(&It&o>92P1PdoT+UOGig9PS@I zT+{!Kla8DI_Z{3#|1~lfj^&Nur}X@%gS+yUMW(}Pd86hwl;`0(>^{cBn{4=Ei!)!> zmhMyscj-UN!Cm^tFfts|IT1gl|3(M@jDsI*KX4fSBnQ9D!O3GyXQzXYbMU!lKq&c= zG!4IkLJ!CEPsUI2-&>q~vrQ0J7|*jYz%jgA-eVlxEpG)Y1CHT2X4LeP4$iTq;$L%c zih$zJvGKz(o$>f7K8lSTjyP#m{9gm`tyb_D-c5fk3j;@-BxpJ}vM_MOPsLC1jSlXH zFNh!z9K)Z6pN9W(1UGQROYl>?he7~H{B-;jKj7eQKX&(L7}|t)`|UF*92R%`u~iQ4 z_G61|!_@kXo9LlyEKYjd`t5dbw|>7%p@C!g3HT}f-)E)55ub>k;%ixXaKuaTQ#_B% zg(F^upW<5_e3FB|>EJFs!^m_vmW%yc3vb{?d-yd54i#9O`MTvD@8E9w>jLnvIXLrH z`oC#$rDu)J_bw;=C@1{=UijN=_@8?Ck1T#Tg$d55f3$ZI@TtnYr=6k@wU3rMHk;AdR-0-Kf@xT$EjGxL+JsS@kan9)|K8uY9j`$S( z6u;cT`6^I+orC8%_&7E;IG>)04(`%l9e`hCah0o><>#dyUT^XFPC70>7dyDipW6cP zeGWbq<|>Y`JUt8XW*HpbFG8B^n8Yu1n2XuHvn(26LJji zrvGIU4M&`FCYo=Doj@U8>EJIqxcgo>ZyEx@F}y1$S5^ruxGN`Z)fxO$Txz}-o|(a2 zIXvj#%u2)OpJl=;pZm;h=md+C9+%IP9o((2DhGG@Qy+jwY(5kx=Amw$y--}|iM0L| z-&A7)Zui3LJdu3TWsc#^*!n+XXj}hhR8A_zq88krZ|naaGR?Xg@zvIUUGhU?>mP^k z&bhcgxi#MNb}^Q+*RBNp@GpRRl~wCB>R?=fpI48+MO=k$$EKOh;Wc&H)O<19HW2AJ zpwEZb90wG496Z3E3#*wI!fwpvFJN(7#zu^>Ql8}w#}1r{v7!~>p56G|;!5+KMV0~? z-eRBRtBA&NChYNNL#_T@>}LKA0?zG(2G};ffWSem zpP&F67K&j;r@1JXS3BzxJ8;lqLt=I>bVeoJIv66s!HXsDo*SN<^{IEy3D3!sk$U*#pElJ6^Y7R6LWwCvM-E5 z+1`R7|2N@N0u2UXZKbeYjHs@}AvX5&AU0y`rARk3)JK?ca6%z#V>jq#;K=w)mOc6b zwA~PK81fKc`6wp}PYs9}_Qk5^;H-e#5hYEt-5LmqP?j=lsEvl#9FHutI;c1a%4oDX zo`9{_=H3tlEjQ;CZUo!`7B=p})!favYTCjYmWq%_A_8(1Pkbz@F2Y^YUgQ!~v4P~n z*5WnP@~O>A%WHR=Pw8NaVCd$8L=41GuY+Q{UHKgDi8xgTMGy+XIF@2y%LR$q-w358 z3glk;OE#OLpLKnUI(Y1bQ+d!WbJ>_$UXT6klcJ1SC{`5S5`<>zH#t@ zFjIv6f<*nz=>k=N8F?j7hBtg3%)~+Bux%@J#;O*ScSp6FH^ovSwUEsh>Jq!4J5*=7 z8bN9EC{}fOIod?qbPct7O2uNlDfFh4aHk#`QUyr!U3Ln&xPXc7 z;@4nkb>Q)tiR(b5gyNC3RcN8;A$uA+I;-ousmlwK zLRA%v;hz#qiHtWSUWpEDyCBi>4Rnu!#Hy~ZnYk_Nb=Gm$^YNa?iX83fiW5ApBE{NoN^qaRtHd_(%2{!e4<0;&$<Gq3nimPcz^gmg4?Qi@43EH11pk$vebtTS;)$|mEjP364#{rZI zC>i~u5SlDRu_E#L%UY(vkDP-Ox}b)1QSG^N>Ze66Zd=%CwV+C^7L@BVLc{zO&{~Ss zMbDiUX`q&nBooC>Kqx9rk6v6iBaMry7ULtD@2FtKM}{EzKXCT6^`)081FCEg*j;Rx6#v{mRo^qap7Zprt$5kw+25XY#yHYbFUIB)sQuKZKJu$V*Tzm9~#>9?!78@jCe%=JmvUsD%`bPscCUdxqhalKdn zQx@lQI>kA!!gQ1$il1Wf2z)xl*%YBXD#lh)M9b1FO9a? z;#yyd(;rHgXDM)3mq*_R*8um^W*ThIL*d;4_}TzGWF~PEp(Tr#c1$S6DWWSnCY15+ zijE1Bcng1WsAI{5@=(Xp2~$EHZ4;*QkkQt~OD3EVTDIWI2^GLvCsc+IuQarH0@N2i zHvu{e&}0y02hnDbThVARdH~cvSg@k~P#uJYpp%aMEZc(4p?#4c9C6A>j5l!KF`nS$ zwTAzJgEM@!z2^i3ou(6!yHMyk>nm<=L$7+crr+=3oG+$($9U=VbsY7fhif~aE)SjN ztN1YicvS!%55SiO;NS9awof|hu+aJRYze@3dbslES01kQ^;-|u@E>|O>x}Mj5(206 zC|>B{%Ky^>@Ny5=dYKV`H+cALLq^Ee@!(gX(obUpbo5B0*5f=6FJd4#noywA@QSy4 zxTbT1gS+kGOAgL_m7Yx=uJnK1!^?$=Q0N{9Kh{a-VFzdWDko2PxTf>6hikcBcW@4Q zl+F(voax8#qdUsJ?D^QG=hF`EhM(-=`H~7gH$1$+;!8YS-;--RT>Fh%JiOkfbBBlP z`|#g9TEX(UB1VQIKV7~}2*9fX@N+y|^PL-j zbE7()UymIQ?(*Ra4$ezW{{{~)kyJyWuX}jR;xa>O^JNgl?+XaO#ltn_0z#n#Sm;S8| zPWm;S=L7IR1mH(<0TPaMy6KN`a5w#m0K6>#zcv8x4Z!aWz#s8&<^K*3FO<@RLauHe z>DTaw+aadbi}G!>himxbJzVAgBo9~lne5?8Po>5A*=DB>gwnG-T*tXHJY3_%Jv<_* zghCftoaN#-i}v%EIXJ^Aex-vS=ipa4xZ59I@8IO8@?k>&{&fd;)BlcxyXpVH!I{4D z?Ij0~ICTEX!5N-Ey0<-C%lnSSmH(9{c<2)kk6K(m=oo&iV(^c&73A}IjDtrIPV?o8 zCY{Qgz85~@;V}~|RBUmd&QdRYjtxJ}3(xr$y0bmJ$-tqQhes@azLUNyKbJT-!)m!c z@8IOU(%<3X+AdZ)xZBUHb8t7E+dN#;`Idvb>5w)$4rj@0b@=RAmPlk4%gf42E6b;p zS5B%Jdab;2YQVE3_ zl)rb}=p=F9Y;M2sy1Hfti=N@?uL$$zH!veQ8&O`%hzz{W+}6aCsD~@QpYN z)vUzhehluP!@|Q$n%^?!CMf`YHgl(zRqZ0?Fw8a8Vx0)S#P2N*8#B#sp{t7*c1F5L6%8Jrw~b;|0oV3}Q7X%a$#Hp;WcYS>fd`LAZJ80${C zv;Yi!g^5pw*RDss;rx;GVorU+q=KbG$tKo2eVFAWD(f+x`$3MDbAj_26_f9~ItkGS&ylgq#c$O2ZpJK?!^&=qjcjLLRx!)i! zl6x-TVsXqY;9=9gVZ;fb0cWg(sOFpk5+%Zt=F7R^#-ihdD<^R64aetLhL9f!{Q?)M zcZJuMLn+baNIW6@jPV3MtmFOOu6uL2u@+TKm4La`XVv!>RxuUBdnip*0ne)nZ#Y^Q z0wZJ@kt*-5S4l7noMO~P3i*pz?>WP)aEkb{nuX!8eaS`B+!L`}_e&msR5S*+c_(%~ z!sfjnu`|stRk?a#`H`6>D>l0jg3J_yW>}TG6^x{#A)34784iJmc)2a=0bHwyfy)k`MLz@^CY13TW849sxF&09@KE$e`l>)*PmH4n( zBM+^q^?AHO-i-pnbP=ri@De1hv}Dkv%{;L`Wvs5k<_65^G}Dk5toe{ASlY@mhGA(l zXFuZGo**`CG&_o1r=zIoo}F4Q&6E9wv{mL`EOa~~HvAf}uHAbv>IfPFRs$m0Ck=7y z_yahT5ht3k<#WL~hsqNv<{`8o{%=<$;;(5l{_-Uxu0xs))MiNQJiR&s z9YJo+knjwpu?lL;@nJ}1XQz)J&$LaKOIFs@Z zedtfki-QVXe0h}C_vTDSeUymiLe5mOj*1KY$e{TTxS z<^=|YCWK{sG5MR08*$|YR+qr}!_e}X{V1wID3v!Dt6?lFBcCrNeS^t!P}i8BC;T5u zVC@TxpZ+fI>k}q2#6VK(U51mf%prn&fw3Y;rWIfiOD2&N5o8JkM49ikPf-C5REgZ8 zvbW<|V@@vq^K$aS8~y-Ik3(N{yyj2{Bzm;56C4w2u6#MW36hhrQ0g*MLWK>3}H zH{KEd8}fTHrk7kE#uHN@K~j}$QoUas2G+ez)>V*o@{Z$sgR+s9W8|MJT8VQ@c+P!O zbs7E}&HE6yf8bp;-{%?PpTQA$+ukKqm1GAZOi ziYS9j8qL89xoNv>9@z#z5ryE;?DAb`2~bwL{55pRuXjM8QQ}X|D{Cmwz0N8@E(sXQ)`cqpMtUX6h^+G|MQ-#kgc!gLR~x%nr>7 zI&wK%nesu38!wk^>qxXzi-c5*^tcu_87(Z|v9V}LSfiiXADZ?QY|A@DC zkal4?*qYb>I0TNBU@8OlPmy4}S1eOM#QHQkQ^Rq^YRKl_2&w3_-MGJ_ZWo07`v(~a zBK;;uj87~(k>GtHq{kQCdwlXP{)}#2|2_Dobu=gY@4&s(2Z(-DQVKVHj4FQ0q_bMn z*~)abFdgZ$`-`At<))KQrK=&RDJB?5%@we-t#-FEO%U{^@svi}Vk;XDX|e!CT1S?S?VE%9vdUg3${Y zBMqtlJW7aDmTA22y{`sUiK?Rs+`CX;X)}PPPR&;i`&>TE2!MC+Q~$r?C;tVu8@6&lh;mzbM^xhNCe{vSBoUaZu)nqhy!Uee;QiJ`h!8%ETQj!YNp zMaE*1*h^YDTDp`QNySATHY8puL(*u7-bb%0F|L!Sy~!2kQVQfZ(=^n3=uJ%qLsWKW&fb zZd-3Qc-rGUlIbc4c zJ7DwAHMi-1&0qbC@Puix>m1~4#Ku8jhJOk-;KJt#pFJRNuneC$C&}ql&9{Jo;F|HX z)2wo@e~muj_JNjL!?ohV$M{U+muo=l`(Zgf=hq#BuDAIwxAD~TON^d%=V^r=*GA@0ACq^ zuM5Db`@~84M5wK!vjxgeD;6wU2IZ$O(3?cCovKgJd}?Wj=2Oe^4yZo0FYAEb(_&~n zeGWQLpQp}K0+FCHHGf4SvBK4Snk=?S(w0jSi#uU+Q!u35y7W-xC(udvIpaxNr>tmw zw|ltC&2=7byMqwRO~-D5>FAotO$6Z-*L3bRu;9nwTEp*kaHdmk@89!+lTM}QC{L%O z#?o2j;VN$>9 zm&=E-4nBwv0eEu&-sa#g|F3ayH{Tuyck_MJ!>cXdp7U_!^UEHt_42-lEC0vZA)nT- z^7A+k*L+X%a1CGM;mZFn1>oOsaF;*dad4MEKXh=HKOcCw(s{HUf@-;x4}a(3%D1T= zuKc;w!?nC~JzVp>*29$#-}7)yXNQMt_@4*h?*!o2vg3zic{zunfnFp;Q!>{tS^<5fA#PJJfnNl z!!`T|9kZ;=TQIJ2cPO- z`{83D;7G>3L$1?mGsCfLaW3phtQf~ANYVs7oiwIK!t}*%?6~J%{mocCxPcjB1z|Yw zz3w8hNp$X8cqSt@gnz1KIs6PJp(yhUv%ELBA-x5tuOu(WK6l zQt=!tbzLB-aB-;yAgL*(pZJ(MLR|KW^LAU7Y{$k~+Z9ZeSs@?Xav}-qn_IdbP3NPm z&ixG8-iPO@8%rTt2 z>UvrHFB#57yw<})T~EYP4Fy&|0`_2Px=*%iu~D86p4ifmC|qTf5Abm2w%E%gBh>Xm z>iTSxYSs1S-SbgLruJnWj~rqCsL`K5e{JA#oaVCLEWFnx_Snp*wNkaboa=4nx%lV8 zdwP3*^8p}@<;UPZuk+|o*Y{$nIWTr}H1mex5$KDo!BslfGl`S`55T9M$`f2plB&)u zL~e`qesyH*SlKf*3eXdcv!T~zr=8w7bWK;sSU?Cf- zETHZniL30o5u`ztNJ*>cZe`8)fskmbD!s0KQ_)H=q=9BSax6dV6FbI#RG)aBZQ>pT zr-~idMvIP|+1q&(PS83J3V71Dqh2cbr0{vtaWXX%XjLNbgsyL@XvR{TZbBNV2lg@J zp4W!09ojXqmK8htX=WneDF64;nvqN3?a5X4*$NMbmvO`gM85*4-DnP;OsF)OoF+`{p2 zvGkE?JRl9L^2J=0w}zj1up?EyaGoBNzPN}FrLRJq2xv71!B4Illc+`F8|E{s6>@Jn z!Tlf%Dq$ie(Vm0D!W;fkm|&i!Htxe?93{SP9ncTflDjzdYoa7@uketahwu$*X?Nf; z9oa@6l2gJy@UopeoMm%XUM?be2l1L3}%jGE03ara-JN|j$`PoUY;C)3Z9Cp9GMMOxn^q9;Xppi&e_z`GkUy# zHeZv~P^1`ww*%W@XGw@Mni$a!R+5`IVC{54Z#NPN(tU0+IdYT5Npq8o6D}%OApo!e zX7mkM$>e7Gq*DYg#yyYKBp3MxTqoRuQ1Bi(7%t)fM^+wLPA*0yk{sBFDp}U^t?n61EDLJFc(OoP+CQyZ|h0bC_BIhRC8`LJZL-QiH^@&h)`~mc& z6?KV&>`F>L>e`xGZgmyWEq7n1ovZD_MA(red)N0#^h(^IKa1jZHY1h4%Dhs;?^-!gjyxG%M)s~7X(UJI{n=|Ty-sYqDzIqS0P32)IMZJ!< z(W~%ZB2st+dwip9bckW8qVDM+PsS!`W*OZ$qsKHek+a^iKaQMfI18!e=8uK~9?bzk zf4b}OLGRP6w75o17mNGR^>rrT+o(*5D(BsKE29=E$ zD#9ua*6%O`|PNp0k-5 zCHr$z`L|mstxJ5IF8UiZI9JLzC1>%!a2o#S7Exikxm5(D=`CJAhrgz0dG!neUfvj`Q3;J1<{s)k)Hdwy7N=fNG0-C;vZ!UCo(ClIgECV}4G))}*ob0bl?v);p zTEyAX&=|iD`J~oxl8n6A1tsz7Ht5DF9-_DOA7A3K+JWR4>= z@5QU%G-8~n_XJX*cw=}0p=ddpCfnXcq&dH5%nzUmQ~aM~NI8vWHI*C#bmIHb@GX7k zCbLpHRvXx2xeVbd4{ulwcBQV*(E%FT(7%{Wj%H>?*G}ny>9BJ#CaI%VvD7rq9qfsv z@@jEZ-j(bg$uV}otY2z5lPnJIcal-85D;HDlEh~X$A5G4VHA=%+fj~PFp5{a8DT#{ zMK)zYOS!4~a28-&N6t1Rr?g~D@|A`+Tu$QMq3r~_H$f?$naE#{yF3~1%G4!ejI-4o&&r5{#61ENpgmUW9{FKuVwanpuijjiixSU7aFikwSr zAJF1{197#9rnR??iaiQzng?Sz3W1rHiUCV2NU{u-sp2^8LNB5DF}91OfgFxYy-8;2S4 zPAB`I3oJpkVX?r!mPUz(ym^jwW*Q?JFJjgu-i2|;dvR{35zZ)dOga8GcNC)PJRDCt zwysw`3YxDwIusvaWUuOau)!#zfj!wQ=Lz8UD_{r9A$sR?Uqu<_ijB3GkeHMgCI!Qd z(n!gM9W3ciJZpR&sVSUG$!)4azzPN$hQG$c389m;s;oBa@P=$~g?*4I7T!ZBR_4o) zEu{~oCq?6W>I0O zaFT=8ZFx4o8IdTy;G}h-KvMgB8*I14O3}l4kWuptAM3MV{_#dk7NV}8NoY3806r5; z3Wa;_!8S;8lU!t}$yG#NCkcUv!zh%Zbt!qW^Ppi!Gi8vm{D~-1mtM=cH{_t zYM2l1zynGpWxUD$*?6pL?1eJ>7VvoP)69fj?p(-;nRtNzkEVQ0|F|8*r{yP{I}!!j zD#j_fwQVao!jM33+zr1Y%%U;-x^1{cw>5?Tt6`+_P0W_D{Cz}kuy33KYY}u3<{i^7 zpe<04G4YIvQ|+||^_6GX4;q#|#QYN5ajI$^x;$HH=3}?E2*t}SIR?zlYsL5Vj#z3A zI!&ogyh3WaCvdo#-aE%G3onSeM74fAqjRdM+ZOu+i-Em!G4z@?1N6D*AvXd>ortKX zI|;MX4Gh8{2KE9$9?2wIbacr9h2Lhkth{6mu9+62M63CXP1jEW@ zEe_AcnY)%yj!*nx{Kad}8 zo{A3VLr5BWcn(4HPBbsXSn6^N{Dn-gzM^}fidbrz!`_vk5G2*&NaO}o{P=^YerZ&w z4VhlR&_93FkkbpGHD^0HN14Ee9Z3J^t~*sS$qqApF!+OvRP2`eGZO=;AMndgUkCi? zx>fFt1~^lTkcskDiX`VTDn9Hn4Pd@CdtS$;4gGY*On`YWlj#Q}DCPy^tBYT*Ixm3F zSEhltc4h+`zt0K?@LP|L*DHAeC-WO-K4b7KLL6VPWY;<=(SLOop%|0W>_z*KRW#K@ zhREzfF7Tdx={W=ptcDwT^1ph?frDfd{Jm0anL}7*IlbP@C77>Xd^<}>E1medCBs== z#e$nx3g;Hg9D&n#N)T^3T7)6gG3q`2%}|8wKVgqx1RGdvbPU& z2&_g7tT8WRw@hR{f@MmEdnZuiw@OC-*Df+-#vo*c_-3qLpUgoG7|zRJT<2#vhj69@ zG+pHfH`plz7L&y=%*4DWnL21fW|f^nSno3Pb~_CuGQB@X<^mkcAcG9{3nb&u?Y;h;62JLZ+Eh z2xcpZGDt<0&1#YGW@x6S_d%N3;nf4-)%jTCOD)gRVQ*3Q+4=%C18T}|4a>&EtuILE zl%;$)HxyxTky|(#Z_-O&@xy+*>@q+aEIrwI@ zef~#gz$v3-e9*8XE#fr6+>*2TMe#fKQ{`u&<81x~d(W47#r@)i)4F;O8L+Yry;l*t z8@3zt^cbvbPjARV+U9GU?2Qji-=K-(IT)7avMc8`P7Sf5|B=x{b!3)`p7g%Vic#v|3RMI2TQ1QOQED{D0ME!bj~w@Qn!D1T$rLWghVR5MQ%M2$Ij1_Ddw6 zS2PXv+mNjvyQtqg26JeLs>NiT;Rm}7RxJx25xL$9L){!}fhr9C%os?=TbxCbFHp2~ zj1y7KSz}nk5Oh>(Rvz2o9{@Dr3k?Flmuz{3%wUUbewor(c#JU{jxR{17~hZgI~1cn zC0F)fwmtrVWSZ*Jc4@^qtnvS7?N>SxCM>v68`=Dl;>Mt?DxS#6=7{17-UGS^GlXAH6bmongD}LAN)bbo{_o!vgjmh_eWRots!$6lV_Q!0C zb&2;tUo@3}Z@OBaHtjZDogBeRb%Hw7AzLlz$!6nY{c?{xw(H8SbbQdIr#H}eYMwRIwqDQ%u{5fb~UGd@}_;^dQ*0N)nq0F zFjX;VNt8#Y-1NaAaycd4COSIJq&-3Q68FOT4u-@VIU5Jp8vVUV7!@ zYg=%I;u^+EBkW&|ZJ){}vkH%T-LMsC&pxbO(c*vI!!8x=^E($s7RDcJYi(`22C3F3 zzh?6OlF9o^%=_^h#kOQT`E!%Y61%w+ZJT_!SJ;!`8aYD=B;zQe)X?ZdNLJ?IU{h{& z5xQ5jLaAklz+{XlGcx;B|i3nPM`OWoVD$RW)csZ~+UDc$2+R1ur-M+H43$t>?3!$;&U+4Z)NI z={i^gA@EIJ5%4Jw$Dy32NnyWl|6MpJL0;xeGWl~x5RTojjog0#KMwy!<2PLP`aT4} zoHH=EzQ2V70@zXY;jvqYIHn#^!VJ0OxF@nNmH$J;5vXkjU=%{G|{Yz{H(p=Nkz{xhNyP_4R5mB$Fo`ium zUKxCC;D`R2lhJcAVxRjaME6vsj!(YC%y@y#@PibNHp}$dkw|H?@{S}Yw==x8Ac6Td z90Jw#HrZ?jJq(V7vilbcXonVN?VKTHeJUn)7j{`J6skr>bt>fiJW&up`ut_fWG}OvGr=UwkYprcd=}NZ%-&{v*1)~Xt#EMr&c?K_ zxM6={uXEnXCR}E(b6od2+cPJ42E}=!SArel{)XpH{7>BLto*aw3CU|&Z{P>*b>2PE z1iIrm<5P7OLY3YNQea>?CzrV0!eY@-Xtu4lG+-}GUzkBlaG8ytAHUJYZ_NaiD~5Gl z8E%;WBp1ZB#&7X(hNV-##$LO6ynNng^N;YxahkvS7vUMxQt{KE`)vG11+1^}6mGzU z&l5gtKhK0vK9m0=@zeN( z{>yDV_5Ap}_j$*#i%v5!Hd(>oTm94c`Q@kTzb`wCd2j;%Lm@HYXD;R6&)<18=#t_7 z|G3wgY#C~=^HhtMS}rJ`si8X5UgvWyUgL$Yw|LycFSPh9i>u6EV)5A?{`VHw_M_qF zS)6iDr}$!Alg@br;S^tnYvL_}X7CjjU*zGu{cG-}?vnftx4CA#9*ZmA^~pMm`~7yW z#kC*M@brh;d;Jf<-M!cPUbr2&pElF@ZUFvo0r&#}_?7^CR{$=1wV^bh2ra#GemnMR zx6vyzJGaw&wcD;}pT7+IwYia-Tei8AyB(Xh=Pz7%1sbQc(Rq(V598^)tgDT3n zhZ_f7tVpzB8#lIl^DA*eS$PPVl}(Yo-BSmjWl_%CDRysnd!j|I(tEqx6IU%+MyNfJ zxN?cJ+Z)i5_GPeU($T(b@zTzPC@38JE;{ygluecEHiB@9tK4odu;6?J>mG#d4$iRL zpFsDl@eWDnfQM`NY}*lPzVmFjF&?h%>|_s*+wlJ0Z7tUoUU>EkbnPCl>G&5)Aki}a5tS^i~H%^X1j9cd!m!h9S-iM^P;Y!apJY3WF_rNMW zv)CXk{U^a!`R{aaH{aC`KB!(C+ztPThikqgawOYB_;yqP?(bdIa+NvZU3$)NaF?E0 z9$s(A2yOLnO@CJa{&E1`AApbGhZLMIC!+%J;{)*G0DO7?eqI1>47_IOsW9XX+A~YO z;eb_fO9RsBc5qj2*EqP#|9d>V-sbxs9xFSitNXW(y8U0flVL*#rwkJzV*JzJt5thuIG9*6-&7@C^a@*B#uIpKm+3oBqFec)6v2 zkB2M$FL=1}|2P_`g!AR6#KB#9COf!GPosw`Jy&_S((^?RS9*Tp;TrzM0Q`3WcmatX zqFm!0+$~p`gS+)x;oxq0J3L(F_Ery9`hOOHzv1A#RQY_*!QFgMCvk9EUz+ddJzVqs zUI2ctgY#1Jeb~X>e4h=#4+h{z@TCh!I^A-Ob#OQRh5-B$4_7()XAjr%KJ4IbzFQsK z&G#_TRmkvD(;4mIn(xyN?tTY-=-^CW$HT);AQuize{29=9e|(X;Y!c-9J*NlYl^#A%xCPtY9-d?It2{j4;&*v?i^YH7;jA0F z+=zJTcBJWy^Ki{~iigiL(L*ylT*tBB@NnhNw>`Ykrt`3eEB%-98= zJ$$CcFLcs(>747}ywrSebnq+(zs14betV~bGdzEE`#d~m;Ls=%0Z0BYtn&GD7T5AJ z3|*UttNe62>F`qNzrn#tg5v8PocXH!eAmI<@b3iRho6kdaHQYmLxdpQF#PyTU1H(l z6<1?Pt!*OpeTttj?HJijxlM{(Ku&o9x^Q^Q@7K)rM8{5}K}RNd9yVtXF*k z>s8baq$1)<@$Z!lS=_@!8oU;dbk4 zd`>Mld2V&2p@GNcGAbHwr;l`V`5gI@U-ikmiw=V9df*4dzg@JoX`f}E+{5AveA2mF z{6~tm(+9m=4$B%AndHdQ!0KEmt~vufPV_s)v=Qg{n*JSltJfJjGn?DVX!H zz+{M0n+VaWhLZ4x-+)@M$?kwPY&sTcfxjj=#fajM9bYg9u|`hqk_Jm9%kodarXLzM z?O`AU-iJ)%gW04THcZ2b4u}mj!#Qih!R%ay^@R=Op5+5 z|7_TycsMo8sLsYx7sBEjw)R>@=jg!BSmo|+9De#C*_wRPZX{tOY^65QjS3#m2iyTvxPD7M}*!TRU4Hpd?{m5EIQ!q0}@!fnugZ5%~~=TTjo zMUfNbMs1RMb{RMs?g_GjY<@s|bQ$m|os?z@ChLluGzwuYteR;xaf3n=Ek86CFlnBI z3F8qwo-^CX4OEn68aTb7B>S+Th2>3XRM*0ONX%|FgXM+r#-D)zDX+FH?8zl zsKXo`v@!ySY-N9{sTJ2c~T4GCezjG@Z%NWFPY~nIMf% zh&t^8#zrPW4ACy~jhLZbU@HwNP7{XBC_lpX2fKR=)bkxc#+N_MLjI6sbf9c88sBX30Tk$zPB%dtw=Of^O*J z-OMbixZj6M%KlyOncN-pll_c;k3e=mEYr;@YDn%gNlkXT?GL&-(BMSQ9|SQF81~;r zgS zD|^Ul*PV8sC=M@dOdSJ*HB)0KOD*0Wr!&`EkzkrX$yc;Yb;z>mjr-TlZTsX`M}bC46w2Z*le++zwsLH(!L-)UYwS zm7BX-c#53e+(l7ojHYr&NUyQ_>F@@&b&|>4lx%QU$wd`NRhpgAZ2zPMA!pNM8>&gN z#e17Rs*TC;)!oNH7__Ve&OwM!oV?SXxN6AdAm=WL7c(26*O|S8*@M>*n_Yg^&WDJh&e11n36rl#N&EL< zcx+Q3>)8V1CMAjVW5#$u5`yexZ8ymeoz$y1J#GBvc;X{g7~9K-g%9>W$RpNV(lW{F zCJQCy32YKE>1V>&s5WT-^_a9_bxKDO&P}n0pimd$FvW?_hkFuu9*4wYk2pF+^np`I zf9fmpYEL|gVT5%44ZT@1j9@aWX~rivf;S*6k~KzflNaeatmn0?<$nj>{R?wod4w^E zpP}R>d-^}%(QM&d!)AwMOReG8Q0zAJy!G7(kMmlwprs@tyQ(4`tvJO?_5+;J+QQuc zr4uGE2wl{64ZZ?GbJ`@}D^x?sBO zGvMxm4I?%VkBu(1`wh+;eE^aw?*HyJ5H{2pZiJM7_BN!r-g7FK->$yfZ`YoRv(1wn zco5t}biMiMN*pipL2j?Dw?QCo{JctlF^i!1`Yo^NSaS3>RE8_&KPiov3(fz#9?r0I z>etw7yY$CL;#RW2aDIMzul_{{!?aZV7>911jo)Z))BhSzfd*XoJmIrkTkrxKkjYUU zP2(%xY;hYb?d`MqrvZDR_&F^A5CP&CGKUJ@W%72lS-!I^~>-_xPXYMt_{WbR*uz64iUY(YUb5X?gUPG`r z#I;%#=MpIKT$_;MY}dqfZddUWEw1vTIHUhHb?i@J28W#fC?N9X4BcRNI&NLvc84u$tg(0894TDam0sL3x}k${ps zwArBr5A}4+=i#->tBwVoOWH)S{i-F)TLo%gzU;~cSBYXfujY$pd&~00OBbdU+S3~D zpoi{&6?8Tq*0IWsucNKJ%(3lE!!r%Kvpihoh4W8z8eY@a_UhwTdEqsk9|Yh(4!~dW zaBU~=2jEB9&Vi4ar-r}S!TMyTI`GbdRIuU!}m#fsn zb*?(@;mU_A1Mq(hz_$kAF9zUmdAQQEQobAxm7jG1_%{M@{~Ri<$DLkyOGfCA0r(uN z1Frnk@Cgss^g9CZwE_4o0r>YkT=R9$i6W-`_!|M?vpG0`Q~H(8u>p9ygLCYo_2Qog zrE=(=qqLKbXB?dGG!1{26+ER=%{BZ-4$kmO z|71r;+ok^v2WNPt=XVz8o5>x@e&pd+1u2wmUtt>lWW=NMb-k5N_Z%dqp}2bv65r8^ zkGJXjd^^+2m+wuw=^n0hUhLuJCV1%Yz4SHTc@FN~Y3cdA zhkw)J-4@sMmH(?8+@)u|gS&kA2M2fM`AI9cOrLA%ntsIQ&*1`}sY@(c(B85)a<=z-^tjC;P1ovEaD-hqTuW&jpoA)S3 zpZLajOdR1ta&OiGIb{|>ew?0`6*|ljnq?&9Cpb(Lif`8dQJz^spPf;{+~Fd54g=lyOOqx0#lN>`AAFXdV>M2o&J!PY92pPGgnQ*V%op+=blf30Y=<&F=Pc!Zm0A5j zdHaZ?e0PbDgnjE@R1MX^Ge{H*zJ>enAa8` z)}P?}>yQWv8f0D+gfSpy(_y=j=1Kw2OI30Hyc}<(`o!f~cGiBzwyfJRWj|1#7<*1C zb~6@%YO@AL>1x79@!tGLnQmqyD2s^H`n++e;>*152N^heGZ9vMq+Gt+sngYs59@i@W!$6=ZMP0U61hu7SM zNOg&U{iC@5$-_vDJ z(@0P?t|xvRzGX{qY|MaJ8Z!xEs(W=IVut@s$j8#oseR@N=k|wjHDyb9?RT+0vT)PD zG5MjuvAWu954eQ6Cf!m0jT zNM$1qfleG!A5Eq@PkwX{XsJvCu;iMSTe`U_I8PptyD)5euT&RHAF5*;r&|e zkWi1qa1uLd&8uiTmrq-a6xdouMy9flAlIG`uT7w1Gp)-e9jmmhGQ9CPkYTzHv~Z?a z@(Zl>e$%W9Q!ZZSipDkL1|E-9+9MRg8-Fckw6LP6}5AYf(B4NFxa}t%Gfh-9V-z9!lVCcL1}Fom}s`4l<1;Qjuq? zFhUt8K}L8ZeyMVaf#hWgRM;mVL7(-cL%Y_VQ4e$TPM|dXzzj`ditAIGej_6;72dqj$ zq+X)nQ4Xxerj3_njpVX@I}!+mZ@dgK`WqygeN`o7#XIXj{~18-yD|K4TS(~Fu!PtD z4wegXP9c=OkjeA=qAzC+f90K*_lA3}!_!P(-hU0kgQe5wY*3Q;(f&s2Q+xYyJ=r?%dI6r^q(V$C) z`)jV9v0LNXmO3pL$tJG%>a)IwS|j5&k)hVeICn=}B`aEo5(G(W! zXqATA%V-O$eG-jfVN5_%SU9GdhOjUIpd~CU6PC)NpJZsRu3WN0Ok5$|s}~Hp4tTQd z9O$u5*$>i{dU(EpLkm1y<>!U~++Vv>`Fz+5ukG-057&0I+rw3!-*Rwn`P4bfKR7tc zrRhwxof#h!ufdP*5)Y3E8VY^U!<9cPJzT?Y^zb5^&euF#)A^ByE1g?BT*Lp;!&wHp zbL<8CJzgq*W_q~R*F1|W9~56=alT%7S%V+l)lPWQsC@pqgY(kfh935CP5s`{;P+V zSp0quFS2-_himv3J-pb4e>VUh>8wqWehq)Dhim#LdbrYaiid0Xi5{-?KGnlj-Wohy z=~)(l-{j%S=dXFV*86=Hr<}-)kmb)q9?s`<|KZ{Ky|u&Qlpm&ZA_K!cXK~8g3HWLI zU2YRpIV7*?{>8(UpD%cLL_%XUEG7O0 zYl#)MO)}3K$+!kOgGYvHn*mz>+z!o|Gxl**bb4Fo~C@0+YhHUTP9Cu?Zby-&GvXZzlPamy( zvAY%fCvdX!d5O-OWzK2#`#3e>_2D>r@C@uUni{R#f<&akyDOuq@}lJCg`3hFk-jXm zRJ+F?h*s{DJx}ryfqpr5l;svcnS3uI7j!+vol=!AcHI&O!SPt??{iZ#%ds!2Ho3RE zl!-PZK0%Q46P=HSxWLo$K3263Fx6f0Td~r#4cRoFh`+oOyPmC0Ze`))(bTMpXyr5A z=Q9ChCp2>V5X49@*^QgQ*n4LD*IQgohTlQSk@)pBH@^!E#6t5DEb$!bY$)0`o?xg z8Y>`;AEl)c33P26B#o49k?&~g3pur^x>8ntE<1tjSmjf7M$)>^)lB1wZOjjguRS{X zTnIij7aq<(OheD%0T_kD$b;jM_46Hvkq1W(Y(r{Yn>RV~e@R{PkK8~#r#|_Ui>39& zx5+q(at$(Cv9@8duTQnGOS-OTR&8olR&A=Wq_*;f?i1@0JasjWbzt0rz#JTz(Uh|l zOv9-uI0p0;gwBbk;-%juRrYE(WU2%uHa0y`SzJ@g3AAD`=UwDaZhIqe}9P4pIh(5 zyV72hjyoNEuf0Zk8-~})j+5x<;x&h@&*~k4{U$wjNc-PASN=CR#3BMduu9V9wS1|u z{v!L0V{Z?cX9=1cUy);CaD9Z1V;5f9p<#N??PQDFPh#8|cbAv1;yRYmdyf5>W>9<` zi)nbxU+;BpT*q39YyLXMQ(WV#KLZa~E_WQnuzi+(l`~>=8qeH8?;00=nfPoaCv)NE z$-m(r>qz4(T@ApTA(0Io3f<~gsC{CqBOUH?T=^IuYJ9dE*ZEriG$#8$oxowt%bFS*NT)ZD@ z&Xr|ncnzn%2|sjYk4T4RDC6?QJG61}dpHz2?2s7zt|0EWBcdZh_5*=8)|~|3ouk$M zo^$HNH`xl%{`?G!M=UF}zm95ni>KR>d}Ls=1*T7R9#&>exx<33( zZ6dL}U9t9-wktk|4B-C3cp`($O22U)4#1~c`YE#%Q4R0g+*kZQE8O%lwT&Aqw2JF9 z-xj>${+y@cPdMqYkJWq+I5@*<`04h7`Lc;<_z14)SUgLz+&9X92G{!AcX{|G zn_pt-f@|7aGGB*(%9hRK(n)`@o~hD65^97F{Wgpz4?4r`=q1jLd@+g+s(h+&Xo#EUS%D zH3Nnb_8_JbVaB?a5Hpg+U^agp%y>M<9IU|v*rurKEy4IZ7bi?N!G1^M^++O*f4OJi z$Hoe3<~%9idTC1PdaJ`6lh2}N)TiRTCE3&w%)?#d9616|{&T~8EIkZ0o$8AYLf`G6 zXgaa@xTliS=8kl-g9-@i3THwyr8bp-p^I^(qqZsmLl?is6=KV$!JzVeT$d<$047|1 z!>~!Ayso$YOqlDau7WL*vq;Q%(Ahi@S4|V}*LW)F;$QBG{1e_Y#3}r`_^GI1WvF9; zVIYHMe0ni`&|A$@lXDA;Sc}Kvukq9P%cF%4ochS*rjQWkaNW=)eu{tD=es(KDIWACdgzs{9EdHu(=okaf z8ePDh*0a)M@mPA#H6s0Y>Wlmj90Mz#l*j(NFlY>{uSe=J)BUAm;3C_Ho7kCu?aLJj z8Uq*G_&Qe9@b1`wSkM?)<}-O6z*ii)hT<;f zLpa5iU-JztxI6Zlp_pjhc>s{+5<2 z!h*tSd9_@X0eG8-Yq@R?z`yC?O3xM#*L-(+xTYTwDi3`(K=q~Niq;{%1uAv7+2B2A z<&!G@V!M{QACM%}2p#U8GrQsJARf>-Qw1u3#+hcp=LV_+g5N0{#;8GDD!8#b$YEJK z?-4I9{wibH67g5!o*T&aB0hDn`LV=}V7D?H(%mQNT8o$nx10CaP_7X)VaO}y!m5sBnRoLUw|h`|e?M+$cyb*R!p^#t@TtSULbttHgOganVVqgr z$1*z!o!C6E8T+wrM2t|?kz8mqw&zS%=jC)CPjznAKs@n0wjFHClC6``s+l=mzm~l5 zD1{@;qsi@ErL-AkcW?DvcXVjrx}&fPmsd*zUaw)OFt7u=xn3j-_9Ip-H7xotC=b+~{vt!4?&`8=m>;sa*6#mEEm37I@n8KggTfQouIHu>in?nQP-XtDl zA!Fbven!mx2{y~*uSy;hO;%#jCXe@(A9w9U31U^pcdZ@RTt$L6T!8eMn_)alRrVJs z`%A1F9y^GfGoK~>xC5uQytM(Q#|A&zn*6x7?CIp@@mnenV#8Lv`%--N$XAYtniK$b z>CBc!e8=L0CpYIAe39#xb;$a}R#<3U8&8D6)GvY8vE-*>$)AT;-HuL8ng(K! zmV4;;=DZINIKKTMGxzbPZrINFuwC4w_JG{&jt_g2d#q~WSo5pk-WA!OmTUI6AZ96B zLWF+>6v%yu#R5^E=~idDXXttWY)Dz^(?zyYv<(E1D&7d(ouUn z@l>ihwR&LrgY1HgTp!;5Iar5e{h9lb{g>h1NNo2{nB8uqU6<&~u-Pz$e8pai;+MeN z=kc|F*@|Uf1tud4OdPCX)Rl-zO7DV?pfB(vHwUZKbDzg2Y2hAz8`qGjjd;KV;&UtU z30+Kcn$4T}9gMwrm;uO^8326r=VEUeY6`n?2BED)8*%b{)2X22{qWjRkjUD~-Ld56 z?npeb2h9T&ZaR@zW#NtC)o*gs-sV{4p00f$>!&g^fe0wcE<{3NJCRs+cOAup#gAiG z2?%?Q<>JLlpm1(cA0My8W85_r?FPZkzr@bJIWNgPKzQw{bT0Rk2_g?*3M;+7H~(dL zV9xBKdEE0@lFR?{JT5X;prm8i0*_=~Z{qLLw<)|&gnLdKF0v|CAiZ&B{sbb zF!U#&V#~nry0Yz*qio!fX`pKMhj={aBV1kbArdQol3AA`C+?8h5?=EddLi%@aYzE$ z+`^4~xM#97s=DPVB)f%z%BsLWl9|1Sscy&BC3}$0D;+uD=g0WruK1};YrqQudJ37Q zz=@AS?4HX#7Jb$|W-${*fGkbi74G4wr4%1>Y};^-6+li2njdrl5F$6c<^y1)vzQGl z673nzsj<9LnQTF-u*`SqV+grFyyk9%#MSojntzfwrXEnm{ftqv*VKSv!-0-P2)euD z3TDn~LNKh2=9Oce`lg~g08or>wdrhvKY&+aJkeZKA59JC{?6ghpa5Ce@mqLfG?o3~ z^W$Nd@VcV*p8lL@61#T`zgafW--=O=%nea~Og5Ow12si^-})+}W75cyDMApw^rs*q zXK(*3>1nZZ6}Myh!*XZ#PV@Qj{ud!|;5!y54dzUV#k4>-tbN4QRt#Aj<)^9R@UAP)g-MOez`x)h~ z??!d^(r~kT$*lHD!vDQm1c2 z&Di>y|3nXG8R*onvDf}O?;V!@Tn2WWmS6pg@Qi7p>mKCpvGE%Rp&9-u+<*(8Cwz97 z%~<(N{&U(#^Hsdr;{OkMUjrUhb*(*+QKCj>VpF9y>Qo1f5+z{J#Kf9`37yDv&} z{@?nItDYZmaI7?^{J)?6aI$0I8oLLge&ae47-it+pJMiP2T#Xx#E(}U?=WIHG%rW@@o;Nv*iO6Oth7Dhw>7_RkQUp6;c%{N z;mdu-tYwi|S$@zGbePpEXV^kzJ`N#adz|UvR?R}X_qB%C`aIc&=Qm=~`G}=6-Qujb z)GhrsvBkluTZ$K1CK%quPjPUjt>N1pI#gxFW4Pww>pcX~x$M$mzJ1gT|Lp^QcWSD{ zNcOMyw^O4+LHZ430{^2i`=BglBw~;O7m#$nO>WHt}PV!rMOU zDE+zc?Vn>PeiGo@|2)C*(k}Qd*58itFu^ew8%-|AF26MT!^@B=SO^4z@a%R4FW zL3fkj_Eisj+$1<$i{s3EK0-S1ud@qh`q$Ye_jY3ues0CttX0PY=Zf#Bt2xlzE)h4!*WfY1j@)NL zbg%Ov)Usv_m>vH*U&S~U{&ku|*wN#3e1KkezD|I;fhluvmokrft&5#>=1{&|mF&deo)wvI6LOBMyBKHPoq_s1 zhBUyw=nLe{^27VY=@JVx%IWRnIK2z=HA!l>(5G>wp^srZUvA`G7z6TM_`QU2_--)p zXyn=#&`aT|kO6|F|J#9>XP4tjeS#n-Hz6tV#qwy%ypaq4J0gbP98wDbJfbQ$WoV>n zIN>V;0+sQ7?9s@&LqO21DzaN@G{QAQDVcG(Jsg3bj;z~)(xCvin&epXZpI~(1=$1B zWz{(#QDK7V;(d{SbDrc&>tm7Lv7l;LP`5wbM;@3sV*H|@PK^5sx5t(Nh zQx8f14>D=~CaC1yq44$lTs-Ck`dqmXH#m3!ZkO*1rRE_%ExdyeEv88E;ywTr`jlA;MKUcG6e+e+Cp`R2?Xl;M+j`!=`l6`PrBD*n239;O;Gfo@d(Z?SixwZ>YkQICnHMJVwJoe%qhQ2Mw zNp#pIfZ2y4*Pf4%3{@rhe;Ss)U##69S^GisZPq>|gU`Fhhel5eqm)%E_aQ1_` zY!+oOo$_5wgcTDy*iw#7UQ8v?YRZp6&oRSBoG|Vv6E`EQQ-n>1K&a&CykDvm`NWb2 z*a%%G?HHW8RN>Psz5}N5d4sKbNIvy27Xa(wXX!-}ljepFY^oSUz7W!*Q}I6DswW}i z`Xrs%$<-d=o&3TuPj!4pq_-AB#;5l&Yo<l4jNR=%!>{{ux7UBwk2QAv=VU{L53J<}5{koxl=v~$kS5PHWdTGUInwD5si zC1~4)Plxz4XR;kxcP^5Z-Wl`?2^Jfper?9n@EK;))MX7#JAN@zdRGXEy{)#gEF#ep zBuzv6Eus>IhJhqmRNz3g4Z+GMqNpaIs7}r60VXqI{P>2=Lhzl=DLmQrgWs&&k_IhN z6c!uI`tv1ey$vA=DFoXmn6k_J(Yh|a1}sA;R$xXjh{LTZ@X6~KG%ih<{mf%A`9@NfaRuLs#%egnl@3%_SI+G8e2s6c1Y!>~2(wXxQBd-=~fsWiT8*hO*fM zBBabQh&X>@4Y*Z6JHTO;gTF0)7%M6`J~IxT650AS<4W`1p45L6hEhnCWGjRVQ=P@z z6Eus$7pZDJVUqI%gcm3la|dHX`1pAKqHK_ZSc`#K=TCTo5A0Y)QRr5gG0R5&X6P=$Oq?=Z`JV8ysG8{Vd5@*~QUW0JYU81J~GX}uDd6fn-_Y-cuj zC5jpwz#ZLK+xEfG%00QGv!%Jl5d3B}hSYHuK6$Qv^)8BRmo2jGIQx1}eIL9S)RHD1 zm+^EY-gzOJT^SnAhgPz`9+Qzn-HmpCm;cI%mZ&Ob%T`lB*%!UJH2a`{-h*m?9~+5I zd~CkW4k9_;*bUw}ZFRJ?A{aA_yc|=Tg*T#N&`2%DZw>kmUFNj_fvE=!RTR?Whb z(?JmJjg=}=U<*e!s^ztW{ZU>-K;s`!8R5w*xE3X2__8RFCxJ-YIk@gEZ_Z)n^pE|O za}MN)#~S&6A9D}-4ff!<2Y24#e0Whal>b}pVgDbPdr4X~e!k&ZdW1}?a!%-uZ z$9(sNmgT=$j*+M4TO)B5zlB5lqIz}U+5gU7iO0qG1;y_=FnT_Hg@fiEH2t7&&*Yg$ z1Ae@AKFi@Q6dF@1r;z5;+!gXqo_Pe#JyhBFEhbq0U*jpzj0;~Te3m-JgwXWyk>P#K zJ*>Cs8!Cl=&9@@$xbQJP)A)bu+`}C<{gs-KJ^N|#9$&H!I<`rZ6AEpzia|B}2!1L* zl}pgvL&_|g3hnYJ`{{d+^S2E5_ndp+ck2HW`&yNQ+SjT)6z3cO>Bn&9q4*iNCSDUt;kV55Lsn zoQvb3b;{^>I5bbt0{$u7lb;11e!0aLd-!K8PI^3){#smhu3rO z*ko}n4}E-t#iI&1=i%m@zJ%xQoRjt=-vmA!jeiTke;k0{9e{I=ijy$#=Z3utC%_Jy zXLx197ETjGvdba-xyh!8aOl>43Ea7@yafK-jQ6**W$j^&ar;(l+`hrLoA`Z$cQ@<+ zH4&cQ;M(o7GvL?_PTnSo-#0`@3TGR?Z#Bl@TdgxmmS4Iky!}tFG9FKY7^X7i}_x7#jo^mrQ`Z*bNRf>3$J`W?cpkiB78&Uq4}ybx1mWMUSjdIhikd_Se)Yz z@~Gp6wH_X`biU}((enDb#WC|FbY|J`-*>{F2u$VkV+Uut^KAHEd${K7cOI_!+V9|Q z`}QH*;i-J$mi|}|S2@pdaJSu4f6+=u({=a8BLB+g8i$U{&n5?Fc;)9mJUngrJckMkZV%cUOYwVbc$JUx^SDPRY3b~>xXMB0Kj`5)-reueISDjWpARJg z9LlHC|DcB}KgWBx$|2+78a^9;l^7d6+^TVCvxn<< zkFQvqYC$@D*XHpJi!)zw{8axdtZks?SNZ>*gS+jJzHhfXk zT&SEi-J?BR(>>Y4mCl(SUTNt!JGfh3oeoZ!Y51!>T>0tu@VKS_RS&PX_#KX3jRmIV z6|>Lz{e^kfBeQ(js)Z}M^2T}UqhvyDfNkE{weQ=1C2ipJXpjrzqa^pS;@M5T`@%C* z+25zKPo;VXi&MS7#qZVPzU}Gk?!x?a_X2!=mz*WwSdvycaB#QDe)iAo$?p7EuI#2n z?|VgE9rz#Fbzx%Y!LBolI74$WOsnv<{TWW$;EOxG+C>{NFHjmDk%TLX#@Yw1r;+Yk zKXLIrMWd|ml7X-c7_rj}B^G-1asP=-SUmgckB|t>tDcoqp3bN8>V1+?{ssD`U|DMY zV89pnha)*U3h!*aMe9^<|DXG!P`McCghCB^Vb4L|+Sl7L|2!LxZ7@r-*xrw^=aVgN zUsWv{3dN-8^SAj6ZR-?Z9VX47_ZdY*y@jIZjV;W&-Q zqe1=)e;QAbkK)4TiO=>~`Kg>JKSCN`@n&H5^#NCfV{w4|eE4ES@i9`-_}UgKWj`!G ziTko=*ey2TB8_Ozeth2hvSZMceHYepC;>(p`1$9Md${x$Tlw+*)II$4-DmDK!~H$K zm7DrdDEY$G-|~%BrBcX&>3XdY3$R=bXV=fZ-2FD1ulL$XW$>l3s<2^%>AFIp6D@6) zA@iU#XlQ>$1Lva3D!i-ce>8PKC)*8^qrGx&NQ9pUvJmG#~FM! z2p{U-t2sN6Fb-G6_cILKdta-`T{{n4a$7_!y-gd7tr+d6w<9js_U^*DZ#ylkAHfw? zj6>*V{y#TGOx~TpKRfN;(}jLi=8}y6En~7rdxtfk%lPY3 zE~=yq51I z#qytaKbY$b8ykSS&WfJXWh|jK#{Dx#VCCTXnPeY`NdA&_Gb@?~!uKLuq3%7&+%zmv zmZ3&&X&c=*G+;Mdup0pVL!pPc$AccZ9`h=fb@Y>(j-k5whGDWJV_ytyE1Gx zZmheqvgd5;tJvCbG-Y-rhPJ0O>3qIm@>qntRnmMTUc%-43yutRKjLUYb!gIu17|^~$$@H%nQTuTAt?pl&iU6%PN?kXts%NUCC&XE@YY<%4T*I9= zmefwq%wpllRG?#lpcta5%_r|6mANE3G`L`_4pes>{jt?rGVb;I4QZ+Jz7{ zmAtN(ue$4EL;{FLB)D?@O)0wA+?kDBir?PLr&G<2Vf^(GTZrhNMG0`q4?ybO~ z;4JL@xTOAaJkgvTOlRYw{xE9$s3Vl2?rQN{k;=TujIE{`H20TO(>9+wqPCPw?Eln= z+W)|P>0#M7yMJzkl*o149d?-mn7Ew`Z_*;&MVtD=r4VWAChQjcR=yhk#>7*T`L!$Y zvQE1qRs+_!y*NwF)XHkA(Sg;+)<)XiieavpS~JU9XVa*&Qn6_C#G0uUSV&v(*cxg{ ztKqlSP;0ZB>x^oSZ65%~+o}^-X9&4J?^y zomIKNdmz_Yrj)9CQd&KQqQs;+R>0MIWB;@f@V`%r(x#>}+fRK14Qn-8Y?ysj4{%Av z?~zDp^+5MM=%Tb*RP`)%YNOCBP^SeZjA~(l4u>a9!t@D+6jC>FCtRdcg;o66xqxh5a$DRH-T$2HEY=KF7BXa;V=5z?88pc-#7t+}SV1JUrX4Rc z8EL)B%8|(9sO+t*DWzp6bZ^g1DbWm7_B7Z!P7NV7swOh<7F(weiIelIeh9kK0>KUy zbZ1tQT6sO+YtQN4j^2WXgKy(@65{hESI$~mb)Ts2`Q(A^ZFA-kv{L71(kuZ})~3Cc zHW6(RWCEkOmUAsVa|T242%h{BPsZ9Oa_-(rW~Z;F{Dc~cZ~TtPx)<@8jF`xT*aMMu zRlpLtbqi3J`mn|5;kY#%n2JiWYTVlU?#Rg6@x=(=`)*NW?Jf-3jEN(>(5zj7JK!TD z8~MJ2{+Ui5B%wk-&D_idTXyiG=g7vzh|KQ^o9vQ<%uDF{zh!!BT5vQ<6*fd0r78%8%(>C7`o((AMJe0B z2BuThy%pvCEaE@ZS%zHOvS|ASSe0u$d0d`I1%bsQoa!6XOiGUHN)hXHiW(Wbk3yPC zAqkStuFW$s5B-U7~8w;+06e%MXps(y_3222M#tsfl|(x4bcA;?XuTtRp28D`^l z`)X85Soia@4aZ5r5n#(7t##xL&RefK1PL9esF4i|F-e~+_*G4cUsd)SPI+KIlw=Nl zT65+ZTf5Hh$I73-mTBp;IJ^Vr%<6y5c`3FyV0WA!*g_<pH91h8Zbi@r!t-k-MJN zCjW>bdYR6=G&Pt078KdazMrhq+IjS=4>Lcn6Wm9THoHd;jzhU14M|a%#ag^Mv{W_=#1PCrEtRYc-i>!m z4T`e}eQ=MMo@dxz8G#t*zfe+)MZq|#<04kav5+e(D3-dJ>&V6`8X4L6RTi}D-D2NI*|>;vAdX}(_{QjqZ?__v{NNkA z#FVjqf>W)UT)kLQ3Z)d+RhHNMLj-+@tNos4cu`Qs&R>|$!g*whBC_F9qxdF25XSV? zD3l#iC_9jGL%?b`o;)f~9?d^Nr5!7(3<<(ge(rCO>fATTjd8 z%lNZh5-xS2D!YAZuI&c2pZD0p0UzP} zQCmjl>PK>c$0nw6E>l8u5nx?SPY+&8QrY|21lscEn4aAe-`j6xV8~1o(~X-xhhF9} z4i7r`=p#0@Q}>%`3l?g8WO~HjWZm%;od}EK(+jxo20Vt)nC={y)Iv8c5L?qh*H`!I z5&2j3$cFupGhXUkk#3J{Sd8@_S&pHFPkFgRelU8bJ6nD zwiQbkE{J`6^7*OTV@o&VOc{1mv6*+s;r7M$y<2Z`2t|xWj;|YZ{ef(Zqa@SK9QjR zKn)#SizPG;p^Bafb~WC#{*vd+XA+ha*696wXaFA;Zm@bT&v$2QV_@7Ek$03GPw0yUEQDyi2EQV5aZ;z56EEF0)XLaY1DeE`*jq{qarEg!m z9<2jD2ZGl{YR0YVq2MYC%c0YlyJ9%04;Pb6vL@8i! z$`7gNvdB<@LM01U2BP6dyU~zg$#4dQh$;*(bKOzf_;gqGOi>mK2}vu; z-uM|P&s;WatxscJ8TxZ1`K5x~I8ZDtf3$mdZmNDgo?6{gqXdnLN&hx#CLQ*g?;tL6!KHkQ>TOqBz{8@r;?%5*}@z|tA?~HcXaPg=BDHOu9RT1 zZhAw{$@x0Y&K~X`Z!e_OfKPWjNUr;tP553My><;GhBT}K(3>GMD#Ql2n=Wx9!wmi_ zxiX3~-vlna3`3-x&|L#A3=gr5OFPY&z4{bj%+}^+1*WDzkMZ@iZmJpA3 z$|NFNf{^Zu{olF{?SH`OT?~0enFad1J9i8oI!A+Z&C8&<@NFM40pDN% z9Pf87e2tf`p>puNanM}2#&6e%_FU}U2hD|R{FE17P8kNe?)7S^hf?KnruZ z3J1-FZ{w0I`3?r|}0e2mXEezhBTn6N=};q5m4zjZErjEwF= zq3w9_+f%edRQJ%#0 zUeC-g@u(O61dFRYH2ldHk9pzQL6A;`hflP)>YLK3u{h5>6sO*jP6I(4iYIYRJSAwM zzVe=U+QXYIKEuP!ddzTWmWQ*ACY=@!=k0Low5Wd!KaT-$D4$DlO?f@JE0%-3HsQ=lf@C6p;xnyL5gB ztTh%aU9t?T%oeO{Uyg-l9lSd;)Ug70)uB!jEE8ABSTH3K1fMi^vmGXJ+)1_-lL=Rf8gP)?>t^Nr#zn;UZz>`jQu0iRQzz; z5c~K?0&sqT=HZ8*8GtVezVZgS-4cAAr9efWH@jAIS{i@bk6G!B4_- z<>$u^9(VBV4({^#cmV!N0Dg$=Z~54zbCiR-@;TPQk9GJt(ZO9h>O<70e_25ID;(U_ z&#N8WO?SP6yXopaQGU8F2ZaB90DdTm;_&I5;NcAt3U&k@p0xNZ57&B;3Ba!jz`x_+ zn(m)HJZaM%XS*u$KNdgLt7->l)CT-`ba=SZ`Lu^ONND(4_HYgVZyr9=hL0XLw&dVc-jf?mdjiRCk^F) zk%y~ZE%We7Nwu)Ix2CH$%GY?|HNV#f;NS4@q@{nGhbupKdARa_zlWi}T_HdUF;?%~SMyB@Cm9OA88RXV46xYC*I;Y#Ox4_7+>5P&ZVz&Cohru$tF*K~j2;hOGt z2j{1Dtrxo-yxhT`b8yO2)BUA~Yr4Pna19^w*12l;iiiGf2Wc)0RE*26Ww zXL-2tGsVL-{Oka{!^2fSdp%tF&jsLHJY4nJUuUfO{Z}u%=GR|;tl{qp2*2CIHNP(h z;6nlUhwVo@?H^SR<2_vEP!oVp^Kg~JEDzUwUF_j1heaN);g@^3hX0I*Yxo-i@GpC~ z=IeU__%;W3-`AdSaMmN`=S>eUvwHrXhcgb3QT*VKL*=jfTo!Oq=%<1z9Inc@o?3XEgr7)f8^mQOaCqpk6Zk457+RodANo@{3sJq<)-0J@o?p{ zDgbW^z%TT0Eywu*_+=ih^6d8T2Aki_4(`5>Z*}l6!t%#sR{;K$hbK+&(90gK{Jier zvuyaOSRlrO@;n(o)#nQwoV+NVO9Jo}0r)Q*+@=2;2Y2be9e@|xg3xkTe$EWQ)nGuw zt9+UQ!p{xBR|MeKc(~I4tb@Dl#`O;Fmispx+?B(<0r+e?52E>ML)q~7goiIMa0u(9 zx4!?dK>)_;5`Kb=TV&22kv|JI97(Q#-hYH!#ZntxL$BO zATBNJ;HtA-e2%5zHz8LkJ>z`WOId)CyR%Jc+GGBCXFN9kH50T5?8uD|Lb8 z%9@@}VZoyH)Sr1^Xh%LNE@Lw`f!Rk+eZv@b*EQFWZao%04Zj|*8kVZ9ZzD`gbsYbt z_{Wmmp96dyY>Wd7(+)i41=>!oNWJvIylpvMm838~ELUsh3kL zqSI$gfc8hn@%o|`)~4;C!{T7or_3Wa?wEib#&P+ZhRBTr+0jD-*>iG7C;Ll|!6M6W zWbGFqSIq>pYnMd2_A!xpD>fn@|C`9Q_u`HXMO4tdfocWSr;R(MkC%nQ!eU_=0K@?C z*d2k8&FKxGCZ!m;W(6s3o4FL0Ah9LOntrlq;rz}emn>;-x_e326|wot7Q~wFT(EL} zJMWtAg5^o9V$uB0rrWz>#&<|lwx~Hft++XRWwbea*_h^RXRJ9pvm!AtrRvg!%QA~_ zQN8fg#Qm@sVFS3$N`=y43r6W+M-X-Z10(sL7%1Y2nPgbA8%w0`4vQ5#8HccF_5G-* z{$Z4SWt=U_RuK}m%f?wN0xKd{P^3{ZtdML)x6Ans*^v^lOKDde{ct+BAl@NvJS4a& zz(j7gu)9Y{gKeCt3uB-@(P(xy*4tA3OON6G=tTBRoJ%9Tk?LJqgcWhCofUCp_7rZv zc4FrVWQ}4dI>zkyWBz;JD~_z)fw@)W(o{Hvp572y*MZJev}_)=i}FD6{sszj8f39M zvTg>SBO_8*s1Ywk*3|=R`biVKN?*FNeSYfh6|qYeE}p+?N$U3HD_5Y{JC~%kEm#J)xEN;rqj5cMbppd7;nzEf0EZnM2DJy1xvZqXQ zwTYtI-XW+o_qdP}5V74RdwgOK^rF#F_^wpbwizpyU(&vCX)Ja3l4VBmKry-mHbKqV zBBn?Qp3*qsZB*j%Cnh4Fzn^Ors27Re`->X069=Dw(KS;TBPrO`{&1_2-@=B9^oV7y zMFQO++o>hibc|XvFcOGxxEL2}R*hOinRYN3dhQgfu_0_W`C@mD?d7+aJxZ~?61;qv z4vchKRpt|=P^^7b~gqv`NOy|7L zW}R6~E3vt!L`&AKtn68?K18tJpfGfu*`*b^WR|hz6;}vg>7`jBz*RVPpQ*&| zduXwvCt`g_Yn*Mj_6GKho(@k+&?VXhch+RT`*W=9%sFc{a}Fw|S4AyciMv*lqev@n z%o0b|utq+@nn?Lw%o`KS4mucQyzUe$ZJQ)#fote5aquI z;n*&*4uN^Wlev+gUpk&;BB^pq*{ulJh<(#)DDq?Rs7)RvvLB`RkHudU+pwX<5`tG@ zB^%(fIPqp_u8tr%WDCVZZ+*2)f`8GYcy-L+y7yR{wwM|=Py{le!4<&B<*m5MMH6)w zExzguZJp7kbfJalTCzNK`?6U3lBG+!LIWchOxn8#SMKL*i$!CNHb$gy7I1 z18lnUqJ=B2h;=TVpSlxWP-oY|4)g(|42^M3*~^Lt-!R(;8O_qx5MAPZ3#S&0sm-AK3bgNLbn{l^f_E__VSE3s(`|3lZX5Vt z(3)!3eV2CK&?^jCjfk4=%wVBkYn~pc zrPZ1uzI-N1=RXDg0z3as^b1#_^S`VDrB;O=za}&|3A6F4ER-9SXn?s!n{a3&rA{+5 z7ScSRETj&crOl(xHQ+%bP9xcordaq&_R=o%|_eS0Y1JryzNom{Akl z8>0F5iMC&Zp^sTk4*ZqEa|PbQ3UW5`H8O1d59Hw~F#Do8Yad2OBrPwn z0z=RkW6B0;ttTTl_(dbQ-;IZ@94?n0#`=O$j;VDVLcq73>_!St5O##p9yfy%28}Yq zi;)Lrm=%Y4TP=ArgB1>Jppn#S`ZhB)G?ndQrR31WjDZ+?KXgpSJ5t|d96=pri6?U* zX&H*R_V@Og%iC9?e_7UacdQc~P3NK|O?NKrjCFBn+H@BOr=78i<*7S6y4Z}JijL<4 zXom1Ua+x$qXo_Nk-@_tTY60Jptg_zx?P*!RQ}BgJsQ*%%#A}k3FbJCzHAHzyD_w_p~2Cz z3K!pskZyDWQY*#Iy3Z%$El>YKw%UcioOlag7pA5ny?fq7Zg`DK@Kan8duFT&Nc5VcF>1`aD8a-x1QRC>?Ew% zn#E^$_(c|P@$mT;pXcH27GLb)T^8@KxJvd4i}N`T#d~l~{#OfHz2j<&ykyyeWh<6q+2Qg_{*f1FhgK}^Dg=VUdSD9rC zFYj0&R~-w$6LX2R7v?1W0Cg;7@0WYH%6YAaYq@;Y!jAiYHo-HcqxI(lBTNLvt8M%b2jFLWxbow#O;r4nfbgI8@JgHRH39f$ z4^P|h>Th28SNz*vc;)AZ0r>6!{520}d&%Pu0r*%lf>AdCOq{APNh_{wV%eT_QHT)zG*YHz4yxouw`D?8d|8zije@&I9`&BQz;@|gh z<>w~>_~QZiFFai7|26XdE!!^9Sw#IEY zHgLd;L-jLhZbRSpaHaF30Q}7W{5YFI(s%3c0tYAU#WvlmJY40o&cR)IKIq`2Q)cPx z^KhmAu7}&(&=E(Ph$;uA(_wLnmGoOI{XP$$XK{BeNF11!`yV{|Z8rP}Z!LnRd!&cY zvf+>QaPq|CL=V?|`D;PgR`U3$7rx!Vp{4+QNdUgy!pW#5arWf3!?br0d#&5 zfd9_JmCi`Mz~S)g;}H%{-ZlIf57%;udANqJ@Nktwm4~bRlOC@6FyF(q+?PAJTYufP z8pnfw)wkQ6@Z?4DCmo#cqKd!Z;4ue3#C9lty%_D`Du;z0u5wu8;VOsq95+a zj$=FT_Jg|}+#Qb{;@O5TK;C%#(!=8h4*kW$HQktf&S4^Dp$A`=+7~W6Xz#aRTg9`g zs$x9;`u%IRTUjv821&RfG#cK=5_9l1cPxR#MTyyoSy9Jp3bwuU$o>De((P&?&j_y z%?CN>0Rt^Ff5oro#hr&pjuQQoM;HbZbZETcO!!4jz+bbmnM}Z4b7bS|PDXXV5Mie& z^P6P$G352TOzv6y&3WF*EjXgdLL2go6zQ^CSnE7Tcoln#(^*iA{7drs5_y&R8G5|@ zYXpEKR05NPD(8$QDN#;%%-s)Zamyb^s80Tq@Yic?GaBnUt0Ei9ApplxX;Wg37``TE z%VtPT*(YXW13_+yG=|v(}lFJ#(yqDGf`T zGW8qOp7hu7DO;KDPo67@S3t37vneu13g!&TF-iwMQazKB?(d|Kmnb-vIS{bef+?3j z+pH`Unq{=7goV`vFn)mUJ;*7f2Pyx@@t2?7!#)_8$mO3YUQYNJ6EUd=l#wympec$m z`~r6IQ%D6?idKKPX+r)E!E6;8zf+v0V)oL6BeB^K=lBQ3H+dn3Bm#WrDtJgYVYN6) zVJKqL&0SLkIfF=PNgQ?$qk8v-SC%f?1WUFtj(#wa#!xEzb2C4G^*{q6$prp3T$njN z`Y(?j7;jKC!kJcsS9ZwiRs6NFDinNHi@Rz|S zB(gCnpj0+&^MM^cnlfcSvaX0}Wy}pen)}O-A@gUV*tN}iUfzR{R|nQf%1 zSWfW?NUs`yE!AR~8;5UQ_%g?oEjKoR#k600Z^T|tk}htJWQe zIsRU1ywvkZ?{Z-!dhu$Ke1(7X=iEx)djUd^f2P11o;as4EbPOe>fk}Qwn}v;C zK;)@N?@nqbkdiQ(nujhQZLDAVh9Z5`TPgrWB()fV-c3Hv#RJA^DM7b67uy!Vy*XNi z_wf8k`>3sCRIbl9Oobi|?bBhsdy6A|V@>Ir(1n)K-)JTh?b`<_O2q?lHj=xf@!W+R zikNX0BBpfney1_+*>HrkE(h$k5!rYYT01rXx?c;1Ow{k^S-~neoPr6y(GZ-a>S50? z=*5o^=s>lg%;MaUW2EfZf-W*1=H49Wh-?!WiGCDJW77(#N~8s&BW#fXdoW~zO_&JL zXo=_?9zzizM=|ATIgG`FdJFx5HXyuJ4WkiH@73~zwlL)0&Xc5y+VV!cFh_9rM6P`t z0;FC%WNL;b!*J5vi<$|sNEDmaAz~T#$#^2t`!g1@?PP#Fba^zHlX}+J_j;u7`*S39BSnl`_1Nu-}uS%qz*04g+9B${UP$O2V?nBtKM$kW|+@OS=|#o)elmYsUO#?FT+s+=U0H zpZ?KM5=&2Fv2#MCRt0K$4$W9WdoTaNq=or!eZFl`H5k?J3*`CZ9G>EUZPEFo$4t)K z6>TWmI5Ii9s%dl$ZHvs@h<=5hh1euvH*v)557RISR!NAr?$G4un&jviy=v!C zk2sqd(H>6~n+qqtwP@N5NKOKEDR`TIXT$3Or*irCM%v>NQqMfO{sK2u!p zgKV508Dm1su-{GiO^NB);>g=%oNRGh%q9~4Z}QUB2l_2Y?<;XZnnCebYe0L}^c9|f z3-V<@IVqe^zbcQI3yrVmj{;`=iC#GMljEn)usrm9p}n@%L!R-k!F~&TB#)R2O;_P& zT=+8Kv)HL7M9Q4xn=0#w#<#^I>xQ-N*r0NX+H!L-UMt^3;2wT_elqmS zj^UFw{grNHT>J5P@5_!+)aY@$C4MBZ6Y=x& x~(pLq22+!TaPv3p!UNhYPgpCyC zN!uOGr=DptMqG7IgXhOZE`fRD3y zm51|oI6vv8o`yp;UU=SgQ=R(CD^|U_Ek%0 zSp^^O6KFs+F@$GWmPLE2{?52h@t&#_bLpv(YXe{H^ ziiHbs%`4;39iHWvEbCfCAn({60WhRP2612rB?ram&h^eSu(Xw|BP!Ds4$kqK&PA1xv;P8z6yL3*l4KHz*&Lj`ld^H8&pKx%O ze#XJw{Q9<2%I8tO;78@~1qUaeO8;LxTCm4_AHL=+GI9I4aLu9o&^O_rT_%e8$af=-B}LHy*C? zdC$XDua2!?j$ddAO!KGXS6G;hL|-0r;0ZyvoYq_a5GE@ekRCUh_4} z;wN}`%HpR5;8O$e6&_w~>3li>@AGg?_j(Uk{=ekm%Kz6rT-}G?h=TJMO)pQjf?cpj1*Z(}} zYxpT%c*UoAxYD`6!&4^vq1FI=X#jpr0RCkU*K~vY&-*r!Nz2a*9-TIekF-NnP@~QMM_i)vRH39gyJY4BKZgGl({pP9o@z~?x1`UN?a_Ec&sQjxjoR+WB zKcvLORQi)Gp~F3Vs>LH7&i7g#F^iMFn{I`JpNwb9PnCmHZteK-XmW5@PZkH@eGX1K zS}vOd@UI8p+Z;RwI?AVSldANea>Bd(`?jj>pv6P|rTcPz%hFN&lO}lR9S^_M;>G*` zg~OM#nfNidE9Wszc$d%PJv?d1hQ@ig>PeNwl~2`^Ngl3xa*l_qo=kJ-yLvLy!Cn48 z;ovU+iyhq6lQjYOw;Y^w7TEm$C;-1V0Dmn2-|yjC?uXmKF3Zd1KVorTo@E}c`tTtS zpKkegZGv5SPPE~ft}D-T9Ngun!NZf5ezS*bzP`=KIDGo5fa=u6>N385b6j59IX z6~%J1LE$>Gko-{_FO_^P({<40AgO{%QvZ1TWn)}O+Y3i>(8cx!Z z{c}eo>rUvJ-`Jmm-J$3@98HG0cbdqU6g|7iOjoBeyAsTzGm$-E`#u7gDu-(cfAX7X zVLtpGnYK>%m+zJsm_UueNlLWj*y;TxV=$H4Mx#pTm!SOkU*l>%|=i{7~fD^AMQyXQVRs)7B@IE4jwxC6yVKE4#+nQZ!{orZP0V zh?d+>`4!_K?o6tXAW+0@No98AO4jjmp0YH~+_&VyHwr#3d}Hm7Zg}cIIWgVhT=nOy zjU&^$nh#Q%=)`n}E?%PLZ!$4sK`|B97mxDxgOrB4<3u4pU&JiHRwLD4BJVgh#&k=JR_Z>z;#VswW#7uNgz2rv5T9=cRv@(sqp>xrR&h z#K`RFy@@=DAv1?B%plLO1Z8sK?1KJiqFrJd8f~V9)A%wad!TWb(lta#yJUdWK| zM%H}`AyHyKWs(hc8Xm?jRtzj(+OCzsHwyf(SaF~zV1W=l0%g0S^Blx}5WgodZ4YB0 zSZ`wIdm6&*(ZY$W+YTAhA_sI}25^37;GQ53u z#cPHR0XMMBh{D`x&MVOI()fpPSHY{w;|Dim{2}tkUg=H!;m1gB)em3&9?pkHdK<+O zqV({=dR#oeXYf+kf#CE>L?YGLq7@4l##YT=aYih&V&VL*g$qK-$>|F}K1b%=C$%pa z+sR;htT7jFs4H@`(f_%Bk8j$xA9LZ8^E2riM`A8L!I^YUsADeu=KqFYUYE<7f6 zuCVUQ#4g0w`(|ADGU2lsb}oI44M_R(vxugvINycs=Mo#zoL1ZP4*+qa`BuDr7>v&} zezgX)XFopYZvC=j&|7T!D{VYI`SE$rah-o`wcidJ>_hg$Z2J8CGuUwH@3Zfwi#)=9 z`rhOGEyMji=fXJ_=iI6unlI`halO|w*KQHlZ`O*(EUx;XxT%*1`wL-xBb^GIc_;@u zSIy@<6h8~s46omI6|b|n>WAWtJKP++!JWY_0eifkIpc)HIhf8=i);RsHqXP&=}rUg z&gp79IUBgjm~r*E7#G9gA^Vb$33aTR-#!78u{=+NQPj$g37C*w*)fssFEE#iN!baQ zmBsy8K$|3*8VZf~aHh?p+QZo&@u+j?Gw;fO z*1?(Iat6lnl!wO+9D2#aRc=EbuJp^9Asm`7rom&Xhbx^q9GQD_i69GBW)?5JY?ycSn&IEkCrq4VU()~jb(A+*-&IVoK~i1%LKWjD)44}68^$Bb0=7UMS*>8>Gtq_bMm+Y;}P z`#X$tMueLu_-)1kCDNTC&o{?Ya<bBvRl~Wk;BX&~b2|G? z>s%6EbOpz!3kh$%I3xeXk`I&v&MBn39|e~N{)U`yv7an%i|>_tvll`tYdwJ@{4U_) zG?eL~+_uU2miR774=$YLerax5aOkhmgOVQ64z=Z6`NTQU!No5#4^{V2OzoL3I;g@gIz*>CDfj_lKp!J>R;EIln*Lk0+sN1IAVcIT`_v z!rkRccqlw7m6^mKiJ|b1^c%_+sRj6qg0E%0Ly_yIfEDI}8DiN=ULfkq9r$KYxfAjp z7g={a0wspvf!64>k{y84bn@PuImUjCo0<)O&XfmpvK0^WYnh^v4R_#upEPa;UXX9$ zDp!m3S{oh%#ZAht@%)Of390_@4U(7M`VnAzGpcSC8@Rugb!!fjf4@Qu@z~2vJ_wX z@G@J5?_l`Uw-3+qAF0+#_ORW?xkM9nHIWVDp>u_Lo5&qAVSC?Wk+qBPUZz?%WLFH< zjp#msA5c09Qc2{FqK?A7cVsPHIaulE3xmvo&txwA{pQTBq*-}5WgyufqOO~rX;PVY z@s;#Was)kzLQmj05!o{Lah5Ij9aa=87Bp9*AtX5d@rdXOz_#$|$q5 zxBl9ptL8~XwRM;>Wov>uojxSQ>RXPrd9xqI=dNGi6Q@)q=-A8rB!%r*u&(*q2T=9+ z$!Xr(i4oB*fEBMI#2_C2CUVVI@JgCwu>brK<_l<|?(oQl<-+HuD6gocQor9LZTqEDrq31zWz3jgD=9K5d4?X?B(|a2t*AK8kFsc&i z{V^J<0{^MZQ)Z!BqPFtJ$l4ShQW0+kyLgn$9fylhvbKCvWG!n(vOfV2(xxU@B}mqd zh-?^1B@kg786^9wOB?&%?!GXu=ozdCeBj`Z-znW`>S|eKElRF&Qdi%*4RR=a03ReX z2ch?{5{X>i~uvxJKuYR57WNP6}Y z(1;JLs;9aN^~_Vu`5HVW;d*}REWPRgpT_c;w}qc=Cq%COwe4@C$O1Vm#yN2(8YkI~ zU>C@+?-E5pQ$G(+$<$(o%Ha|zNkrp%dT4thtF8AEOXZ=q4a>Ron!SWAsn%BDHORWTE~38C2C+|1Z$YQ~V=)dFr7bvMPP#X>jO zHAaJwnISfGDda|4yau_*S_kz|@*@doy)c6*cGc@a-F)R`!jjX>qpUa;cz_ShttF2) z?RaVAlw4&QYHkZw@MB$Jb0~W{$xW`SJi4b7EksJYO5?Jd^=l8Fr!v)>%v3@mSMu*@ zQP!WqoZ%^@o;Lj?GtR)QZA>2%Ig_*1SDP-uFg!Gn&OBhM&6K+OT=ymlz5!ubP>hqx zyh%}QWtwczdG0UyBTlH}zZ$9Sh;BcT8u3=sh+U~7j4c_t$n=NoAEZDacHO`Sqf&$@ z$hc4-w%cG4S3aC9@0qLWAFeM!)kyB6~KMvo1!Pj&W9K@C~f5 zBZ(?z)K*JYt`FiNME*_b>DXFxNj6-JJcjGGu&mYI8R`8rVw24jVh^^08@rCv2!tdC zlQw}Uf>6%IINxq6*IGLiHhP8T@*x%gMUEy@^pTlCzUA6v$`p7CRm;3+B(f#fB*sP4 z83{vOSu6>uZ+O!rFku$d`EovbG4c{tfeYrAKj#aHV#qJ$ZZ$dVM*or|wdpuT9f`cm>Yhsk8#O_Z-YuaF{ON~v@@NHk8puZKsF-m0}D|;F$p(Qibb39Rb{hv`;YDUkl0jA4Pu`?JJpE=-#_RZT0Nb)VEsyE zq)Q?X3{2V2Lz>wAr7;`+i5UwRHix!jy|@`kBp{KgbmH zPm790^y+8Dj}HS=!UIKAKC7UKcb;n;w-B4loHBR`HYlMAk*D`kl;` zMeSAX&#hOD$i^w}pjVUJFmo(v%t!r_vDrGpuR|icpF{HM$EN1WH`&(+^csJNtlM!2 zdB^x#B=Tk=7yc2|z5Y#zStuG2uudFdM4&~O&ODfXid56PrE17b-2;){7Ep9NZWz4) z8_2H|eX>?gk+t-YNu49VX}C_nL}}&y?37-Mth+;=nc;t$Ev^}?GEDU&Q*zJi&{790!kW}I_nRSe4NZDyn!b7f~z z#2jU?FKu8hOkLLoI?4JAKOjxnU2GCC$%)_~kdTG!h1Kj<*$%AcHJ}T^v}-_I^bTk# z(%Ev`teg5}`aTt#ng2H8u6+kWD@{Kc>N(ZOocSSl=+35P!t2eLwCk9m9kp+o0dDut zjhYYA%M7br3ZW^D2Arw4P5hK=ur9{{Sq zDMkcfl1-WOnEE4l0-CDr3Q{ggm>e6wPC}*%so+)Tto3ILWZV7eD+~rLu z@DhPJ@@S;@d+32+QXs7dsbG_r=Kk=#90k(dQ|pJoK-;6NVUJ^zM+Wxvi_&5nND4;3 z%;yWTN)@vDMR^(h%GFO`PN{IxIUo#`sX^4nXi%Z~^K8l!a_`bEWi zg4HVfju~SYf}PgvfX$A6q#Y*p@VWjn%GG z4$v;4=#H(}kPcoXowywap$3VzL8@_X71I{Khax>`)sGT6>_B5`=FpBrHc}UHv`u(Y z1#ixrK$#kCE7|t3Y{{1j+O}zUZJTAZO$y)9wtu$!hDjA?ONl<3g%9?^kE1!io?0g= zIyeDA@xE=kw%VPMwa0Qh6X|cZNO|jfccQMS`*5e=3d2`&%wemr2!@98@60Q2AAAUV zlzKr2h*;lX9E%k2pe_A{tZXhH|8 z0fn&7W&6sd%Q`DV$=Op(&PChpJjUxIa;O-~%Qecz%@AMDw|A0+|%1;ZTK`-n%$R=VnjX!a8 z;L92h&V8Us2^I4O#~5=G8%W|DJ-J6pC-Gbm*Yc^;!8jK}nnCe7=kFexzG4$_!Sp98 zV9%QVcn@b-9(r!D*Z2^7z_Hr$uldx6n!cVd!~@b&_0w>hZ2T4l>{;U}+>8rfCVaN9 z%7oDLDgXCl6QTRX8!Cl=&9@@$xbQJP)A-dI(4PIUR1d%G7_{8ZBdxUY^yJ6qy)Qe4 z9b+d)H(BCrV`KQK{8TPMHW6F7hz-Zj%qjoxr=Ne|T`=7LO*RqC?{GE|%qDS_hsq~z z@fglLRL92Qn&J7JhvKY1#47|X;I$TKJ>{X{*>^I$Rnt74u(;}thNsN}!`I-0bgzLSsuQ|;w>J|+rOs` z$a+cdU>lHri)(qyE&i^zcvJ!BJe+OF7x3J*4blGMYru!2@!bIY2LbpU0r-6ZI9BA# zBzGnxd)mRqgtjHLFp&*bU|Vu#2*#I7VPev?V*Vl+nP3}d?y#~1Rwn-l8xw@CrQr$I z{c~;qgiw2DS7sTuRiS;#nOyph5sWPTUxLN{hz`pXEdB3T)`euw<{5DdrYd%4722x^ zW3u{x@uf>wFFn|D1%bfJs)e%nfB6E232|RW9z0R^w4VBVV8rl@#}T%@WB79X@Jb-Z zu?|i;s?X;J;Gg&KIO6cw>fu`7_Xglaw!$d?8oo6E&jjG^`eFuAI`;&G-yMKIAAtYf z!;_NRQ0Oln9=G^WGX5@Jg|9KuBx8WCgIP=D%*W$D})3${8dJpGw9{nDElz~HEusHRcbg0ujzF~37?L_=k zKI+m&%S-X&tnI4e`d)W(0KUV+RSr)F;JQwh`C)mb@Z-^JGpOmReEz}WT7OlZ84p+4 zwL5eeR`b>6;7nKZ^=S`Jk{KMEJY4y?$HOa3@X+G{`0F07`cupd;n4glKGwsPzQ1l) z`8+Ei{P#Uv!|OU(KBgSBp1$gYciTgMj}xWyt`nYgRG#kMCoY~UK_DD{etSJ!%WJ2H zs~p07aj*paQxK6RX?9{ z(q&l9?+Xsjbd~>KdbpO?N#1%xmCu<0_yr!GB$GH62jG1kuJm&ruKe8S;Trzy97M3=pJk$l&hl^#@9#mP>8|&}msmO*JY2(n(Zd^T z_^&xQbw|tnUI%Bn>+!IMSK9|qdw7Gz_j-7Z#VhQfU*)F!Pw;T1lk#v&CUl{PD?b-| zxYAkR;mXf457%<(@^CGeH6E^daI*V(&q4hoI;VOqs9%fXpf<^N|M zu5^Cx;VOscJzV*G*~2TXeEtxCf6xwKRGu3CI1g8SxYWZnd^P~z;^E5Y*F9Y6e9yyG zAAacJO6NHbFR}UkvxB>Oc$8f{p!wDCF%Q>tD?D7~|1A&Ka@=Wg)kD>{T^_Fb`LIVv z_3BxR`+D^YFTBb@J1k9C@#8GR%&)75CpoyQho^dY+RAgHhuhmwjfYp;@Cgss^1Uzs z?+n1N^l;_pY7bZayw<~2o=0IdH zC6@j?53jfQRRQ?59j?N!Xc__k;AY;Qx@W_Rh5!WLBj zrGJCks%opf}#Ta(S~mZ_~%N9y$H^g68q)6 z**Yh<&e~DI`U>H=!h-oq!*YKQ!qIeP4ekdTaf6xQV~dVYWwC>ZvGc!^5};xICP@lr zjSRXrewzg5BV$Sn=vE8ia+|$`p?w*`=SBm&MX~GR<)k6Ez@xa~fy-ihS$A5`M>tcx zANQPKWOmY-Cx`BXW&7tCw(hj<7deUk2Cjv}MBTW^#&6>eoRT07y!J76W;g97-XPRp z-_N+y`pfDEXe~N4c_3UvWO8r)c|%vt?0b8FY7mO_jmFZ!>~Fb*VKE{mL5tai+XEp$ zf{#cVSYCj0_7-{k@&1w%re@<~61l^sj4L^o^TdbI?4LXi-3R_QT#7VNIOGqcNwROK z`TWX_1Zm#EKx45oN<6DP(fKwHHrkA4?2`@eCFbz4f&B zo%A8le>>7whI96}WO_9oCm~K2RI0!J1_many}-$72hPY0A46C*u#~86%$<@P7q3eU z-3u!w8WFH4kegE@8!k7wAwNkFXRJmznvncR3Sf2*9@_jQk$?&FY-H^fV;ITEpb^IK zYv%)CnUQ>Bu0Ecu#qtqcLn)rXi3ctpF;}6_%pNj2#!30@!oYPByeYFIX&0ox#Cc?{ zd{p1FD?h-QbLJg_896et_S=|KQ~IAd0<1HIzU^J#RWP#lZZsFn6m|Aas!HN^#3u`? z#fcI7klV({#~*2&@N8r4dr4R^BqJM-M5)ki#{;xokTxfkX^ST*eJXP@7r&{o@0Ure zG`R!xA{!nC2&s~45;jLk#I3-NUog2PAsAb~)%QR$(r7|pUi} zQwHC|l&F;H{`j2;21~iJ*wkG3q$&N?(PZ}VWdHP`#@Yva&V|kSuTq)EVc$^k8vmZ9 zSwZzvL-!Y``62S5SlOfQ07WaG<7go+^?z{5wn zzw9S86(E0)vq)J!iCotWsEhQ8F|sii4nuU2zONuAEqlsf)eM6fW*CW4aBvqf`z2g_ z@=r)`{I6GCPC8P8xuan31Do1#vVZbWvVZP#`hF4T$-b0Hw{v*vIlJR7+7Idce+5Y@0lnoiLua5!m0>rW!lK*OnfAkq^MV*8&_cu z!;EPRnQb=XY_+IwsseEC@#|z3dkewcNh+BOO&u5B__1-}&r+(Ca|yyu9#{6ylXK-? zJN22m&C)+$P2Lu8gVPv1j$C&J-YUt$Be-MH@4`8eD?crftE|M5j5JLJLB`^k!7*CRmnsNP)oc`}$P>tmk1Y`W|b*NYb5$*l&F-(i(p5dFUl!IHZ9=dNB-U zi%~yYcO*`IE7_kuV+hY$MojL%>gb_l?e1ju1Gq1RBcRRkpMo{?_q%v{HL`IH_`+s` zD9Yo2(3bRd)KX@ZX_2`Q&WT+64I#Lmd8+Of$tzPn3Oy-0nDrn4d7a&qeK3)2|6wS1 zb~L>lOt zZH}nV{mZdt#2CFJuPn~&X%HlusNJ>o8@i5XgSClbVE%^gvqjFQ;f*VQ%?E6KNR`yE zL{0immbgT?2d(U=sYPWY(Remxc2aetNIlop_vdU^e+Z)%8E-^3Y($HYgdF}ib#DV6 zRduxuPe{a|kx4WnYSgGx3ld|1fW$;)V4@S40Ifk2iwX`}R8$Jl(ux6vsN*<6TdlUG zmA3XNZEb6joi_+@%E{yk{^;}DbAa*t}WBj8Jd`hJl33P`3Wkg z=(Y5)`105LMAO)UQ#vq_!Dr;So}c-o;Hn}}Ahw{X6QikNjp;IgWfc)BC)?Oq8Vgd( z21R?Zk*c7vupnAr5kc@MY)iWqcj4dR+vj(vM4XP?6?p)>@mbE>T+`aV7kU?$w~*m> z;MAS1_=U?Vf`1OdXQ4R@cYcJC8EIzlSyaJJ{5B=4ic%%NN1UBl=g0I`a9ezyeBiB? zIk($!4Hac6a-)KZrCwwWu!Q7DS*evUM`O|rKOEA~2YJV?l%iC9c(IqVUw9u+?q;=6 z;9|kpNcJG2YQeAEkVw8Twhk>+dpVK@YZ^GP)9R+*8oK-)CPrn_rj=r+WLTu$)%XZv zq%jq{6_r!;5|~9OeFUZY0PPgk%f>Sm#T0$X$5@gXPWLS=jNcwjw{(6sHq~+~s$oF7 zFjlZG+WQ0yH-0-C;VF;p#7`OaVxU8eWYG;P4tLeU3u~e*2n7>M?P8uN5PB)PP|Ave zIW--*gWFfeq^n9}ga6hzc+22z(ZO5cCF!*3hzB~VlCo1X^Y-gyuVR(sc%#$B#=1{p za2wr#@DVn=)6F#)zURVpmw^L~cs*-DEqWC*N6FA%GW+x~ED9yh)vpzQADf=}OX$&V z2n1hI9rOY=tUQc_xV5yce1r2G;nI<`do&^F4EAeEeFnPEkru2Tj$l1|CFp@np{s1$ zmpDJqw_^ET?5XVJ^=kH1uu-k-wU&`fyS{56kdE2(u^mucguUd zrX(y3ABV%9+&c70+b?X+G+@OoB*jvooZDElVV=F}YC_--d!Jc@vLXL)VO8sx`bOld zwTHRfMR)ZPvv~@0xPu+4mUl@*M|K8#S!KsdH)EEoVr*dmH#CnwNAuLV1n(0YQ){C; z*2M}J`MRrnEZp@zvyQCMl+y$2mPosKCEk+4XR{#;FM5VFXbxSo2z6xzusE!objAJA z!iu{ghQ`#oF{z4Q%|C{w(Ay2IXDO?mfsSHh<;upowN6n{b7fU8bztSPt|NZPwa()* z4ZlP>E;GzGBwZKFjK^Zsic?@rm7F#mtH&ewo!`)uT*t1BZ?vYci}|ER$%BhLC|$z=(BVjbO$bR~ zt$4RS+kpYi+Qz|nTz0(mc8lb&llkZ2MK53`1D=?UnI55=zja>s!(AU^ngBY_ywv+` z@8QKKKphgvT@;Y_Og>vs_J^HxXr*+38z=>i+e%y;(wusEO_7^K$A;DZ(9>vPc|Yu1 zjloo1;+b*yw&O9#4c*WNr0CV5v9QSP+F?60LHqjkMMs4*>|rsX?aXqzZ>-LDy23Zc zV8MdR{h$IDE33kb%h%O6B$ zI&VZGs7U4wey5m4$c}C>5rJzyLD{i3?k1TZsHVyvVWYr1P?t2s>U>Eo73sgGh_ixt zP`4671(D1+*&qz_E`tjyP4|x$hEexqilyD*MVpv9cur!T`uDCZ+^2WBRC5Zua1Uay zevitZe=<6wtR62i--Vu-oI(R)O)ypNb2=^EP;qJ@^ttz0;dg4P;cx_LT;iNBux{ib zyqHZe8W5J)8?A22M2Cx3Pq!LRzQ~R&22%&bQp=$Y`xlm!vIUQ(*2d}{pFi?~o5VPn zI-3R7M{@=(8myo>SrM6-EWcw+s_JHZ+Bp*KEqN5x*zr{FO3g*rcbz-(Q6OUJ`rOE6 zDi(v=EGK}uEc<~VdXV=)%U7d1I#C$RHLbv>H~XdgVuD~2CG`L@1J_;xM|(N8XJCql zLdWJeKLBdP{;tMU$-XgmBI3#Z*w`2AMA52l$PR9_yHIs^HqY!qZ3mwvmsGeW`%kR#h9Z^?lsnPVYgP)ELsVap=(RO;cxSi7^R7NTfbqjluPD_7J*t z*8vi89e}}4qqGC@XwN}z2L$%FJ2mkp675}%26tCe@{?$4%EKYHxed?u7ICXdS;OZ& z_hGjIHEJyjkbEJAUoGd6)jax zC7)GH)=5AyA>iqLPnef7H}m)npseM9p2pILXGMD$TW&JaSp#+lmZ11O1CV!!vKD4V zfzfQXf-au?G>Wa7Jws@(GD*^N0xqEPu$=2bLOpV&%UU6tM?MOi=B-Bc1xr*ZP#M(> z-5w;C413%fyw*V4?4Cdu{4|FjP6X4qUZ+CH!lR1CDQ2cW-y5GOLuf#c)EK05(2L4HYS{t4_X`OIP{ z<@3*0g!B8P>|Naq9dAq*#0rZBU~Jf!!oaY)1MwjIs8KjoMZ$}(ac*OY^cwI%W3$FXT@P{-3f&YFs{jrK9io7tUGGE_(j!9Zb4n zwytw7P7o>g_03b<6clDaum$j`@WQFUH*Y|)B*#_-ahxj?- zbXnbt;l+plgCv+_rYZ%e(GhW?VQ)4|7qZk_ahqQg$9NfYmUAboouw=KAO=m9E2`tL z37yv4(+4od4rhW>L)ydCyzRKjPnD;tQcR7PZe9+VT~l;F{-SaZ>RpW-bzSP(D*x^# zmOi;>UXL%tEV9UyV*+E5Q~Y>x7$*Pj<{T=`h~*A1sv>dfInK@zps!%b#$}3}3rphz z;_PNQm*Y$*sJa-UZE}v(&3$6hyb;P9%@iHlyS8p+c=3Z^sN=uXiUgt+LFx|xL>sXl zF+Lu{?~^iY!z|xvbr?rsHfG)X;T2EpwdwKA8+%t`f(BuGCqGg50;Xs-c05Q8sDUN$ zDLjqnCx}jrNX+-Td2d`DiuvVgJb@3;pSuke{#N+9dr)JErphZw8)RxEoYgd z;l_7ho_@YH-1#27bI*ZW-S)Gu;C5)+4RAD%K>hG@KeZQrg?&CM3LOXfLO<+z@$VG6 zpJb4LLp^)F4J>(!45ZNC2XU(E`#rC|mHUD(_$Z z6V1Q=o(%ZQp5H3ZTiNKf{!WtTVW)c>+vWMzJa$1wuOn6_u$6hA&GgMn^bL3T>2iL_S$xwA->~Q|UXTK9; zhjCwzUq`~T+4$1;tl4wih9Eg5Qyi*0{G~4F+LU`lDTq@Ricbvek>L6%#V3ejS^5Pu zJRBDP053Te$NR7>pIY}m+tX9l%Kyi*N0oen_(igJlX#HN0tRNrVbiS_zhd!9N9}Ey z_w=}6TC#o4h-5a9Y4%$qwRz&0B8(|QoZ|SO$1!b{GBC~2F5%HAV@W7_W^-yy^o*v| z$I;1%W|~Mn&CiX@p|en||U zEheM82_r_{R2RJ?k@}e9=UMF4ce@AiUKGE%fC0HPHz>=7RA4ZZK%Bkw*DBE!?D`>| zMaS=PiI&04GC>Y1*5TLnR(YK)xdF3(PhzdiVq9`Apmcw97M(6M`2{oRuQ{tjKW#Z8 zw7}kc&^Gp1YeWEB9Ius43_OR>AVnemE$Pdl_pIKPsl&)STK|p8aM#7IAG~Ll%a~(k z&ogF7jj5P!Lbv!n_u#^Y(%yN~_$h~3>A9uRx`qKAr#EFP4ocVih!OQy7KJl^fnLXx zSU2Pc2JH8hGIz=LpM-p{F3hI=5wjU(5&%4PW{1%98{C5`)uf-2ho19R=0u(Q}M$jSY9+e<%A+R?|m{_ zx51|rUOXT4QgB}u=8US)+dU>d@79nn7T!@Ygvoj@*Jui{1%1pEiHwQhIj&}(>0KVH zTQ0F(mWh%@Gm{EjjZ?juFTCx$KAQeUIbIWVan3Fqc{CQ8f$5i31(O1E|H~>Us%EGn5Aa6BX~jNRB=pt%GE^_ z&!&zaXb3`|l#fLct=ld#oL>|30-!!oT+PYnqM5H1j7#EuMBV$o%8==XjeLjFu)brR zC(kKG=i?niG{(~+dH48i=Gz4mlZb6u_ly?+!l8Dv*c}+SL-UYd$!VI`4QFJ=*S)qs<8_%f~R5Kb^K%dBMQRAGwAZ5&H8kC~!ok5uBDU267DaY!b^MwLMtNXUlvGW_FsqLv}nTM13 z2wxr~|AncK_0i0%0^H+5l!kZsKppwkaYhAfp6z%_MCG#Hm^r-{v&Z6uM2bBxaz;IK zZb3jfF?%vD8{7>OBS;cWj0+Jgvh%V9Gdvir+bFy`p75$HL>hU_+h&fx7f)mA>Bc%_ zCKj0z&MZc^Nu5W+GjB?+W;?e9i9@>0nTl0$z68!z2=w~^Z@`=-gP*|HjoQk0#FGt- zRp&$r8)!Q~JOo~GxH%;j1|gaTK*wU7lLqYoc=E;G@cGTIA^pA3(g$UV%Dg^c66X@w zPc$>Rz$Y0?A0O?-Vjfq6vBK*5mdF%eK(L1bIy}617cMT4I7k{NX=5V!5~?gc4-K2E z%`tUQ!uF#xXB0>r!_-SY5qRW2iR8N=2FdS2SnHB}X^5-IF`1%+ld@c zr^nW(+OPgheEuF4CbFPhDqd|YSRNbVEJ?g2xFRweZnhqRKV^qVt!iyD5zIYa?Q<>9 zXexDU!d>NPQ&j<+{8?9&cN49{iNsfJY)IAJA|t2}+-2{xP8FP6QT8rpP!g{pH~!PT z-0_Rhnv?%P>@K!-wNGKnYeKU8H>mrMCuS<}?$WCa3Q#%(6m7L@uomH6mS>3bsJZ?O zUGvp=GvaF=jvi}h;iO#{tVdXlL%ZWw2gAQDgZ2>W- zZ+*+N3JZ0|Ap#bRwX|VnwC=-L$~i$efU<_iIv&N>+~x*e78MT2Sxn};y2Y?_L^8- zPtZ+t{I=%;a27M{xsLw9bL`m$arrhljp=#c3ubqLp1L`?i}4y=#V0aVcQ+-kg1bYL zg&JX3&Og_joE$nWjddJ8MJxb$B!#6nuIBNs&})GE8(#b^Je74rem;=Z%kFwKGq)Gr z)jnP-r>3h4o04jdn5uSx)S2k1sqzAe(uuy{V!ZU|I9sk0-Yq?ftRoedq!wvnrU8-R zeBU1d`VxE_F+N%T(?sfZcHEmX?dx|^id*ogdjaOu#p#AfiX#c$^^Lf=?dD`p6GE!u z9rus~meH|oq?#gnEgNpO+h|GIhBaW*;awscZTDF`tkqo}s~7Y4lx_uFB6%DW@fGeXDVEwc_(@-Vr>0}SgL?x< zkht8SQN8|m(zwQfivZAcPDr9HMyvW$wyIoiSLb}!FS0BBuXc9Se z92^w-ZaKSx-C}uwBhfJx$5N;ml*1Lz|Bdz{l=-;@jdfU7?ck2b)hqhwn(Pcv-*T+g zjje6M8;0H$BI?F8x{cWe*oiTm`G*^D_*~#EyO#_^(#a;#(R5;t`!LE}#R2h-&(wa# zYCT-4V`8!bujQe)j!`Zn(1bHLjL#IIk#;QbOxu)KcCw$4y*?aQtpf=S?5KZ)#mBjK zDexi?wqI)+za0*S{gnu#8xV<_N4gdrYghMd&)N99CZFv&*0ACIARh7UdUK{~6|2xUo4#3x zPpDdhS~!@Jq~CUMG}XTFGoJy`M6apZ!Z(Inu`m~vbV(>$@Se2uzF!GmXy(79agP?( zE)aQ$_SUWOkA%DSaRYxpIB!nA;2pM4a?Fs5o4xF!2>MgS)e%O;k<#GPG3YjhSb?G$q$GB{!p2zG`eH zwx1gp)V_kZ#J#Iyg$>s>)~yzmr>za8tqoOY@~f;fakA;TH_+rhizZh~4D%R8X~7}} z(F!<&&eV6hvcI7%F`KbLyoJc0qjAff)ac1Te^M0TFS<;haOMh5)6IXOi!(vqV6$N> zZ7x_hK2tI*jty6^MSQ0s`=tqIBAt)7_h)5o0IM~9kfgf*o}VJ7GDXgOXui-xpv+tm zkVWQN*L$(O^rb-#Fkl?!!k)WKH5IIzn5p`d*%_2by@9M`%f;3p5a%4l^@T$&OF7L} zte+2%rrDW4`T%_W>*oS7t><&?Zn6J26$68X4U4fy>vbxt!+Q?JiVm@io~IE+Q|Bj8 z8rJ;Sbj3BDo4gH#7tO*_h(MHUuit)31-sN920b3AJ=j~;xJ>OptYeeOn6c@WBZ}&t zn>(@Yx%LCSp>)beIWE7er_?ciMdvb71K3k&f0Zj~Yd;aQI*IHxpeUCpU=C>8eX0J8 z=Ik3fcAIDV{)^LI->|S^nA0(7tceFh2pkH=!r{xSKC9TNbO&}yAY`hmd*AROwE4D0 zBz3J{k(-h2xfrkbz2wNY25d>O#W8!bY5D7g_+E^AQJ`ZMPVZENd(zw7OWT&q+NaH| z{PwijmtJ`3H|JDdb^+s!R!%>E*7=uCKmXF?h3C(45lKhRoDPm(JQjH9fBsF@hh5JI zW$$0gFR>2nDs1du>EHAE(4+2~tatw}ev_4-VfAl$|2M;tRzk3}7I~H7#f-nBII`DrV$;g^&R0K1*lHMP z`U(%l3G+2f0sWQqokvv+zxq6%;V~NjzwG&lJkR&6!9$6<*XdKmlSN|dLH_J%nj z-GB0(G2d4*j;0=3F1}ABuGjj@Mu2#!JfKgqn8f`%-<&RayUxWoRr+e77q^hj0qu`` zD)Gxh=||$6c*LPO{6xVA8T@3y=@)n?pD{QmpBjhe@Y4iWJyZIG;G+!v*98~z$nvM1 zk^g8ze~#cWgU=8=Zt%+lXZk!eKUd(K{3kgyhhHUli@|yM|J|AZ)dERGe!lEo{vvm8 z@2vjl6Dh$}e-!T$T(5(_g&}I`p2zob8H{_X?b98=EpI;g>pb`$^WdB*{4zeP^57wT zDV_|?LD19o=@(A>Cc>W1K|E4?S$CETPdeQF4nyeE3laD9A_P6X7(q{GBIxO5jCsnC zr{7}4)5|Vnw9{`Rp6T$=h0_`96whBa{d|Tyb-_mUctp->A@8`kGSx_8WUZp=g4}QGCN4uvnNow$z;7Nlk|G5U&@_x_Y z5#jR_gR39=v%%GtRv29M=V^m$y}V*@rQc$3mH$V1aQAs2VIbdXa1EwZE%&toq6!!8m6Ee9x?RFf3?B2 zT(25j>HlT$7=?`EV}q++eP(dgpT5i-4qGqbJou12_{j!W`NRya<@&n8wOp6v!LK!V z%x63FV}q;y++%P}cU=Gv*895woToA2f3%xT%E?Fd{B3+?&F8`ZJ!PPJ^)rK4GLtxdV{n!8e;ZuoxzgYf&nC3l;L4}J48Bx8l|o-` zaOHE9!BuX94X$zF#^!N=yo&oy|Z(9bk@ zjo{xgcuep`23P(0p23y>?FLu+-x|C@_^&d!(!XYK&F7~ESGo1$033(PQ~8t{JnqRt z0}Ng%xQ&Oc@;}bdYkq3;;NuOh>3-eds<+b&uKAf^a4pwm23LLVFu2-Fr@_@OZZo*% z^Ct#ZyI5v$rT=e(tK7N`u6))QT;*`2Uu2%GN6r6GgO8H>Iz@2)aQ(O*u>da1p53jl z2l!Bysy|Z#_*Vk>Hv@PPaFz3S46gb7Z65pygKK$THn`UBW`nET-Zi+=e{66qSD_4@ z)h;Sg1|B2w;PnPq{!Ip_EO<;dxRz_G!ACo4ETc5I%I$W8mkRx_46gFO*Wk+kA%iRb z6$aOQKAQ*sr@;qFes&pL?P&iJPoQ$v{2XO)O?R-tRi4#?vpR{zJloI+LtiEM97C`8 z+yMPCpjCaCAHd09^K(l854LNY0yycF&s%x$e(wEI&JQd7zyKcXXI2Gp^4IzrZg9=# zXoIUhoN92@A4F$zht`YoIn&??PZsj;zjFDn68yqE^a~8G{C{L{<@0-kv&=lY1=o64 zKJOVk=E+0FoQTH3as}(Re*hbNcsU+g@2V%iF!*Rkh5ot0O9a0^5B^L558BJi0i5zz{_h)H z{fXPS13Jy8>O)^nzz1-Z&mjh{^<*I%|6c8`$CFQm8@-?5w8+z5BI)kg+ z#u~gv_)jpn%B|Jl5uvwn^p*cbdFZb)c!Th{#o)^S&jzm%`fUbR`u7d4^4w`~&1bK{ zCkg)pvB`yp)=Q1Q3>}&WA7pS%_jrSAeVt-(tuGtDzf#hjVCc2H=Nnwpz1ZODe=aw; z(qC_Il|z@omCr2(*K#d2_-M)he;Hiu?qP!$3H^%(S3YkTT#sRy-#B z4;P&E8?@_40B2rQKdTL{?S8$%HQl(uwZ0}8T;(~%;7Xq~c%|h3$9eF(46c0a_W?AY z4;gyZ!?gxi`t=4^`R^xtLD}7;-1Hb=aFyo~23Py~s=+n?Qw3*zeHH(;UAQ2CGu=x3 z=P}>ln*X;9e@`6>>0VaNzvlBZL$CJIUj(J}n$H6SxA{CIfCuwA!r(E04V38x!m08S(+@6drM6eAJ50N(>#|PXu>V7)L z&FKb3ZUrn?AaCF^*x9fZzoGP1mHsZ}hamVTb6b+EP-Rw^0@k&!&B=|8SoAwCS$=!8 zZl|n7=d#3-_1sZe@=C{J>8nciV0SjS@mu9?WhD!=1^ifatXW_*UcQ~zy{7s}0aq_?NI14+)`lko@jV$$N6ooTKqaTT_EiCgEaAVCduh@P4r|dSCh8t21 z`$#sk>(qVOPEA!@?UP41X6|diPL#gbmAtnv2D7h=%ey9X3)SSH{85BqP-4H-T5H_p zn4f!3*K$d|U!SSLHL+cC|5$x9BFejQVYrL$n^|$xochbLM7N|gSN%%0_#jYY>&!v2 zI{{JQ2Vg6*GqK)hqS!1u0*@mA;+rMh(G(}N=@N-$&MZJ=-TTwc<=l|X-SAm`Nkm$)`|^j; zv~0MJrss0=@u%~zz+zHY;Gll_%xEsTS-RoJnh`F9ow8Y$>?4%v0@<&a-E@yVQ}N`> z*jcy{8#qw9vWoR0kaYX?MNTLkxA{WI>RXrly6rxN`NxVPU_~)j#bYaII$HOE?!thu zYS)u#`_rM0m%M%i?BwH)YRwKzgd%QEzS5W(2UA1g>)w-UYZ4pic)oW{{Z*BIwLQLE zfThc^^yLA=YecZsu3N!I_87_zZQ381>-tXeaSx34>O3q2l}aM|&Tuzq~~BscSY=KBtbkv!Ng7&iO#4 zD&Xsw7G}O(V##M*ya75fs&`YeC?)laY+z@8sD5%*Q5yDE`JC%m_$^v>pJG#Pq1Qm4 z#QZAyJ6D%Y$!DUyk0GvhntQVnPvav6pT|5EH&>LbLe)(U)g6eWVH&R#Q*v$zHl?u+ z;QOcI8w$PgTv532-;sNj!M7F`&4ZBed;OVs55yf2tdK-AUis|Uyr355t7&GP$Kyr;-i1Wy-Z_vBJ%T@ zt6+F-MXz9yxw{`;+=$i;`!~m6A$zNX^p>v!pU=AY=GSMp`d}OL8mQHStdyC%Q7Jp5 zmBL zV82Ki_KVQ^?H|#89d`s!J<{iy`p72T%M*4ItuMbWyl4o>AO|UAc1NDy)r}j?b0Gr6 zW^3z|?fTdPDC)uueV$Q{>Za zyh;6oEkq^Mja9pqx4v}u$RONtw_GO-J2mbjAp7pnQ)wz#8!yCGk_nlL?c7*W8BhJo zZ5?sjxc1nO;U$G2^VmXyc%@*orU2=~U%2X^T~G2fkc>dysPL_ro3IDt8P~8p8@_Qf zBF1@1*S#NJ)CeZz=(($Yiyi@YvDHPtcCik9lo41Iu>Wkdd56q&e9nl@S<*?^6_6?ls)VseqpECbcM(5QX7EV;LbnQZQ z?#;>9#Al67H{3Bc)o`=5_WOOJIgULyaAUMfh7yTFq_NCsZ1va38sWvqQOsVk@ZFj? zqA{S{OHpobuj%q@>nDf2WW!yLf|xm^OH3r6r#xI2D%FFndTSUP20c~mvW2j2;+8;o zjHh?1q=BIbpCk+`5Wx`$_vqEB?ThLdynX`!-W zFHPOlQ}jk)(fOOAB`>fVTr%by;pY%Sa&))nXHUqRv8YS(NJE0~eV5F(nU|~%K zpF1O?^->gBQ)PhN+=eLHT_x{1TlJ%aHGbch6E;lK2~s*5jh)Z?jZtgCQZ`0;r`|Kf z?f&C%BKZWfwiFZy(fw4mhTtG?CZ zqU~^THSY#Fc{$ZfZjg=wvge!GzoFl9i?eO)$~qz~VIbi52YNNer!#(_l{&V*aMYco+Zu>!Y-~1wPXb59avDWl#T($NbiQSZ1tEeW|V!;ma zRfy7J*x@Iz!>i_ouRRk!hSuW@iPqy{(}a3X3HY9lqvPlaWgZ?46AwmaaK%yuMg#_L zT(B5?_@rY*ZW}2}#Lb122jVpMu1+MY{+o%G@2dOAhv{G=Uj9x8#^bAI1mZ9Fj(yLC z2mmb}f<@W_J{Vx#gOD{ka$3~uNL(ptuTHxp+VB|kKv7+Ld&SseqhDWc^!qwC`VACC zaWP|^EH3|J&o996>AJUPoB~=8gsw`AqbV{V4CU(Opin;k+AV9Gfb?Mk?GViU7uGpBEXn$-cz+?Wu;V zd+MBn@MT|9R15~8o?>j84E-PO?s2ul1|yi@obO!HKJ7gGw$JvzGxTis`7@_gx1T?^Jybn?TKlw6 z^?7sV?73<0{~vq!RF0G>kJ0XL?oYlwe8s$hquY5vA2XApcB+71*9760^ZvvO@jrNs zl6MI~jOU!U4IZ2mB+q=$PYn_aZ4erY3#LCT2;yARj~HC@uWB7;JDxv(^=b4PHdy*E3Ko`k#`eUExwUr%dbr0kQ zVa`|aN8!IMKbNF^S^AZ-fb31&4<0uC;Jx5E>Hd>@_%LY)z0K9UmW!`ii0iffvN*(5 z9~I|12I8s@$`Rht;p&qWA1Zhyet9Tfhja3YI5dZ|6(v5%;8DT#oq+Ob6kOCd%fCr* z)hDH&AowW!@=*MAoHJdvD?AiG3+Kc~6U3qTG@KKUIW&h~BzWB5vjk5VJl|fu1w!9q z=s6w7bXyI+Sa8}m56vgf|2Ovb-NuB!#8WI0T=mIa%AYUW!}l}X3-005_USI*s+&O` zf6jw<=fR)IgTIgm-;@XUd;9ouDH+1PzDuyb4?ozihpm3t+c*3CZ@b-jetX|gZ13ZC zzhT(ocOka;U4$)u7k^=kpWC=M%x~ix9=e!3xX+J!{zimmpI1F}WOmQr2_d)VZ&b+b zA;dO6$9z}~xBIz2Ljybg0vr7p;@I!z!&z>JpF8{FE7+RvNrguD9mFdkwC94xr=2q4}wFS7_h!;GD_eVd*F4!OzQsUt)00 z&ou_Gbg6|xe=@lGpH~d7{>|aG;gHQ6wh0Zm2 zrQlZ>T+4g2!PU<%F?fUU`JKTB3jP;^M+9GGaIKdY46gL=7+mH2fx$JOMbh~5HuYKQ zOAW642N+!QQ)zIew|fUGrCehTz2cJ%u6({3z=LaP=LB%(U+KSNa4lCR55C0UDxY5& zT>1ar;F|v@46gK>46ge2y1`Yi-Zr@EkKJpi{C669#Y>93z_orAKhoeTpRXER%Qe#A z%IEYv_zZ(Hr*L3aPLB*Hnp?@Y1-p|b+e9@nj=fNut9`|Al9c%DX!ABZg z%hhOb&Hp6^SNU`pT>ZoK23P(+H@NEUGJ}tneE!McO8-nA{I3Sre7<9FEmwhC$&r(@ zBpd2)aBWY^4X*hN?oDKsYCfkM`Wi{#QiE$hbDqIlh5lB9tN#BY5B_U|Yd-&Ea81|l zanyW18K4jPu}uM-y^mr(p`nIe@e>TL@;u4l zDo?vtQt@OS`dJ3od@eM&>cb5N*Ye(!2fxGMYG1!JxZ2kr46f-ukOzM%5B|Er6C(d@ z2Co$S6N8rv-oMzNXg#VO4KTRY*AW3csBb3)aMCLMc!Mkd$$9WOdGG}WSHE$;;JW5f ziWTZMcwBBgZg9B_J#TQemwh;)fkXMLoWp`sZV~*~avd1JDFaQn+Tfc1I)hi@86HuC zt2~ni*LqCn!SBd}-(zqs*Ix{-{699h=D!~oG2>AEp)7a|G`P|qVQ{6dGI*uq5(=Gc zaLs3v!PV|28eHvevca`pW*S`cd5ys}pEu{hZ!@^^`I*7BT)#4Ssg(E62G{aFWpK^U z#yt2x4PGVuKQVZX;Ehyp9K2nG|B8<@xRz_8;H>wr;J@m>-OH%?yd*#$^c$G~&UBT} zZF%sY8eH?a-r&mTuK~O=!2e$Xoayo&j~xcr{O?ub@2j4x{+uT`A0r<s5pggtQgmo9g^1u3wUhRjS9gMCM-6 z%C*c`6W=#ph;(IjPprOl{weX)8d==koLq^;p%an`MC%`euUX|j{dC0mO!>3m&F%wN zeI9}jk-Ul|4(V7GLumL$d^1LQhPy^_0mZ^qg8~asm{Y7^^9vYj3$U)`ELpkzX^6uIL_Pdl!fJ}kLa1vGvv#AtNG=xz#V{YEIVP;~C<+(nZaw^-!55O-ZcQ89@m&C2POu zS41ZuKV;#0)-l({ZS@4>lMO$TRl<##bNhPQiOHhh$a0_N_YOZc1Vkfl~>&j|E9LM>7+P{TdvJ5zolx+xcPWL~{Cl z_%jpV8(;qSLVT~P6D!RSqMIKA8<$Mnip5P>2$p;WOSInP_xl)K8>>?Jk+2Q;>h+ch znaI`&nW~)=G7Z}kncB7E{FgRLB2CNx2BMPXTttS&ak0quICYqkSm$_Vim(Db0r>z~ z8`rgR+!KK$xPq#rn2#0n`w~y$x{cS^oq<#Nsu-|+@VPI>y2oNlE{t>!pl01#soaA# z_-upwaFy$fkk`Jjo9`CGJX`VElh%`AH78T)u^iKXg$p!(*%)?b>;i2AZqIWcb8@W7 zVl0T;W|x9TTSJ7Lwqv#O-r%+a|A&Gj^CjHW9q0~{@R=WgI1GbstL-}h-;V&fQy;KA zy_DQ%4$3GwQj}P&WGg%!fYZ*}jSNkme2fXVud@54vkIQT_ z7xQx*ZR0Aje!cAkrZPRkgj=5`aFt8&DK2n-mVfwB4u}{_-6^5tsOV&!J;|oXit=`a zjR|cf19<5?A)@{tfeWd*aN9+LaMgCPOTIrCBYBp%^`AUHn^J9kho@({O4`QjfACKa z{~U`yWyfksnTE4q0Isl9lXa-LZIo}-;ebW9;*`T>KI0-eDh-ywx1CqRERDst(x873 zh+ABqh;%olo@An1;+gR^aeT6JD{o#tkltzos`_nSo{4XQwf>!F6N=Nd199=jkoL%% z1P0^c^`-)RnjjYGrWQejt#9E@>(NaM*9>f0xVjP-Wk+Yu`LsFpB(nXtriCkuo8YVC z3s;O{5h8mxXU-_?+?4QsC*c?S$rtSsevx6q+kD(xdEApgt6a_a=WC(__>Rp*YgOj-u4b9lXh0FKGb}%+H&P~B@qFpJu*XOn|GrkDl*V_vp z=80y;_Vpy=lePEy95>_3Sgr(3$p$nGNS2N9x@_xmm$Vy=nTz+9+Y^%|4{5uSX~?)I zp!sZ+9}sFZ^Y==r)3p&H#ug}~;4H}BJ2gH1BqTOP+L1)MA;PwVEl6|n)fkrh-iw~f zYxu(6YvVH&@1l9>#Ga!qg%dN89cXYeSQ%W4=Hhh#RiC>rCbCJuXG8r5idn3Ds`(^2&vxnlLi)g6Z@V^>&s-bvUH{v7>2LHke<}y&uJP98fX(#}hV@;*U z@_%S5nul=P5S)3J{SnVjz@IYy$=aHlhPNv^?j7`=?R(Kk%3NYNY5Tfs5|X7*;O!*5N%~V;?dT-Olr7*#F8(r24*CJpJ%{uzL8_m4k5pL0p}t(<2}! z>}l4>Ef6OwI>86%)^{S4JK%k5=zUQQId|#`6-`(58!|I;Z_c4+&fb;%K1){}d@G9N z(^EOi*0Q)?IiB!-gSFrUjx?7f(pf!l(n$CnN2m+$ES>b+#z%_gQ27oQ5^@~y(WN@# zI>ELCrr361ESl~N0xcr0yMP1``C-%SbiWcxG{U^FvFXQ|Z z`c(XmqCag~xI+BvO4Pz?_*d9p*{H0abhaSwGTUakGOE124a?TLaMv1a-M|=SU|@_Q z``e(MlM=~YaF_6%ttgu3oi2*>uJBDAwnsdmwKxS`{+7rR@mH|XTd7@iA!xxyaDVdf zT-9;qd!*d?k;cLAHRE%b_*57C)mG@hTb-M<>Y)hJ50q~VqLi)};jRg;1$j=|NBE*8 zZc{um=oH0ysxg_^VIl6%y&W66uSInZWwV9GNZO(CnTBVmmQ=)!`=mYU`4FV z7?*5BvnN)R;P~V_*tS^|S-7H)ilFGvqU`L-dJ#CSnUIY903EPSiorJtv|MHtTk2g= zPE98c#HVKyzeIn3W~8-g`J3?F8@ai3=3ek^73k}?d?l3NcMClOda140+0a(imu|z= z2kmqS>=Cg7oIT-d*6aYvM`qm<0lD+pV`78ZWAu;bENBP6jO19Ny9C3Sf)O=L#mST> z&a}i{GDYYoI9fM4h~M73x;fdfkgAPV1*%~%ckF5ZUI)m!X2Dq&#pLCW=31>Pk$e)ZF`Dfw3m2}yw;}O0BlOaJJy7u2)FXAlD$@F?#ZFkq zQwEFJ;`fMXKSX;gtA`)z6`~2rnfIYirra7jH9Z9_tgo2AyWtn5fEvT(0KSyH74Elt zLT2U&R1n8naL>{mq|CWxtgWOB6$noYS?|YWh=o~Td>j%b#$PaWy5b*U=Y4pN8Y1jR zljmcn!PwWZ5o+ajn$|v~!p5fQ@R~?%Ia{ux17a!kR$WRvUXV@|>0An93o9COdXTI2 z0?aAOM^5*sb|*1B?VB(0pzwEJRZoXo-hbaN4$f(U(*opoGK`O(6Kp#_L@(t$7_Qi| zwXUacv<3hE8)U>!WgcIbIk z8OHNN$7QOH#89;#H&*j2w{2Aiz)?ASb6p!W7S(`#|H#>8j&gXG63-1nF{Q(@n*w!> zTA6R!96Nr-`g3}ehNF>sR@jawtM5d%H)L{gDSXU8X;H-0Q0aFvds9i$`VQ*VsVMda zJDnSou65n8!8yePUD;s&?QFWDePe?^C*<;yIp_17US5bEy?7%u)5x2vEc`mfWPf3* zwAG@1nIeq&)JeJgqY)Mzm6jjf^sAZOVf=${2g2v}uIBkEXbN0kh8O6Cw(fAF!Axv7 z`V_4n_^}M+09OTf24AJM=iPF)@pXCgzAfB!GPU*Rc;%oT&1vhCZl((vbFy|V%D4TD z*NVLo$&Z_{fzfk;KZC|DR*n5;Q8aTJ1|sjMzLwnP71bNO*Iy@f4Us4l!G1{3}9Ib#kKoZ(R9m>8l@q)YT;3#mwb zYCmkZD>)|k1Ulh(4x>cDYmNmT z!yHGr^4BnY!A(g0+vumfBu>17v1{2ueb)pYcvfGyAOxt3@SGG)67}Bb9OWI zWBPMP9m7c8%^bMOMtXbra_!2hA9tNx%pRN=_fM1F$&tIzeQAMcKHD1EgtZ+h{ek9W z#kF{#?FbHO-0XpK{^-}j&0{Kk4T(!4yjsET!T3zk23{;@!@&6iwsUMKC>2D0_^ULf zxGclS(j}jrCUAL>RwCPtEvB{Aex%mM?hD!mSli}o+YrrM1xss0+t4?W>}^VJ&siEe z=V`UHW(@hyhowD73AmI!-FQR>^7h`G{7|O?8XgquYRp_E)5^`sBJ3IVnUr2Ijf^wn zOLMaT*h}n;E<5Ot;2~FS9GL6PG_*I7oPyE1pDd;^a)AFbRQe@+T=zA6>N7XCN4r9c z1htIq@#WdaoQb+t=u1cOho0a7r2Rg|@ov^q^`@;a>xzHMU`JwI*+(#r z&D5UAn)39h={~T#Gu&u(9W1StpR_C+fG3?-z^@Yyo2(Z>h?hF(O5u?*r*1&5aP~RQ z*(Vx4Ouup-R(k8K73H&sos!>2GIm6Zx(^t7I+W`QXQbbykq)Qrf5R!-4)AK_bS)+d zP(a@eC4W~l$fv7){JLujiE{}u#^hYVejzx+qk!d7y1v$5FRPKg+I~~ zzX{)f*7UJKO!RG90NjG>8T}p3f>QvkM^e^DGR3#lT_C;bUx9ms2cVB!8W$hyjU(G2 zc^M){F3)IygRbK9%sHRsTt(ma=_-5~Q7l&}ET5B_n|A!-z}Zm;2F)%NcEqN_byVx< z8B7ji1Hdx7zHZxaaW`(>(Q6Qj*oOC7@}4hQbR7%sK16*KUj{la;^xH<=8dQD#a-3y zf*kP9Oy+uK3AF@J0l#)SEYN zOgRir0WbP+_Z8l);8dWiNn{{#7@vBA87MhCT_F+TxJ&>d%vV}eucUf=anxR z9K-?4-Jyh>rSNJWT(!PHdDh|OK5zK~0e#NTP~#TewY;++)6u*Pyt6=XH!yd;!@shi z+K~qDD;{(1A3m5J5C5LRI}pyPtweyWH}Gtkgcu8V9pomQoVdiFWcwnnrmbUfnH9h7 z#^{K_5RpN4)(tG?$UC(zHh7DBX>lR8uB2A?M*c~oa$ezYU-SxB!Yho0R~QekfOi(~ z3O(e%EHifRFS>@)bFKjf?=p&)+F#-tzR@?HsmL&0nsLreV6-bf3NOc9>ER~8$`vo? z9{%8Y3*MM+sAx*Q3`2Sm#VEhmy_E26lwuFj*2TUYHa=Ot$jyxf=z!fw`!;m9xYytT zI=K&W4icRP(ZriG(_e%Vw?szgdXlB(`_P2lORsWg!d`QsUM0hLhp%4SN}L6|;!^R7 zPUIcen=Lw-THypq!)xdR)B21i*N_`s0I%H#_=m*Ni_)F}@T&cRzeBu=27DX^PCn&_ z0B2y$w(`T-3CA>m?+G=gs}9e#-i?EIqhGp*p^o63ch)$>ND{hm##tX^;))XY?O33> zceka1ClhC#6u=QQ@i@&8*~!YmXBR`Ycn)*YZcg&`VCyFQ!Hl1bv@!a;jp#-)9O~+U zruSD84Mt1Oi`RJXXim%WYBOelFf_oR2^X&hhXVs?l1;E#zHDf$V@IkC6A@x$E`wr# z>a+bl9fV3#>2)UD^(0#Mz+5*>joDj94>y{PFrD6Zn4Y*p2+-BIHvoi_%47{C9XS!p zi0X4y1euja`ZW%Iqbd1LW9GbqrcBE}>3_GtyXurS#2V?Jgxa(r)VKAjFJ~D<1 zkeZ{{MaEu3#KJ_f;dYHvh`}#K*I4&=yujlm3_2ZC#J@~K$rZIowx zvT8A=#3boh=G;CIq_1`N9*TZ`nQKYBq|i@TOcy^IW&WKn^ILEZPV9WLVQ_Zn(r`U3 zwGr|_#L!VWd9eTbIcvG0x^eK|uttVe=hYH(+*SQBSqB+Sc@YEj_T3>TB&k&=2FWV9 zyz3^toy|H$40qL`8a2`yBt&uftVw&6ot}2|kRLl|qaj4B70L<`m2oy&Ld;gW2}-<5 z;}{e&6-| z(Sml;sxYVMvWW?l`@B&9Ua0b}c$Aj6Y!7#OYC5uiJX!IF3FzO&m%oLnMEJJks)?Dz zYRsf0HpAf1_9L*`Zk(YJ%v!>Jj=Oi@2wfFy`5E(aM5uA_>y4Rd1@vyu=30N&R?q{2 zHg=rr-nb!rQ8la3yFk3cX?NX=9nROW+u^D$-1QSTr!1=6g1Uja9LW6e#5s*@?Kq<5 zB-?FYe+fVPfXUYHIn76nF;AFDfa^F$=8?Gw;W6~*UET8b5#Bfa9k06A;=1((d0~Qw zS`UymTP+6#I3V0Lh4Td;VlLTry4luZe1BVD9am;N8ryFaX2upZCzm%RKVXk&8MEmU z4Yr3))Y2Z}{r+{?7Si272l{?rrFh$r@paBt)~NyBSbU!?8m8~kv>{Y?eRC$prt=-0 zRdn{BnfFihOHbnCjMbIU3%KyKNP0guH1WwpT+b z&1tur@g0EDh&kd;Z87hB#5=(?OSlsm$UATGPULVtBUOl|3ZaTm&e?lx@ZV#Z3-)ND zzK5t^+UTefhzRLu<6mg49B-L|YD!|VRogFDLJk6xwLfOLIH}Nfyz@}7%@?Tvu;j0@ zp>PXQ+{n`{SHTQZrigP0&$0EuTZL>p;p7SNV8x<4l_oY#61xQlIDe*v`1~>5b3pcn%tgVVOx-M0?gVO1Hq4zZ}vi;O_ z#VI)j0j(dwu*2kPn%pr+LG!@IAm@ibDWeup?nkvJS1en=4L{6bAIhn9xa&AfvP)Z_ z4wr`N?utJNOkq0d(VC%rj-)C1F3DXg+Pgu4P9eCLOBx>LYzW0s;Pv5e>2eNW`9>rE zt-IK&u;&5~)sMiZ(y3`H;1yoqFE2*#=4D>&^wT}m)z(pHXix~eyZ1@^AE^g%Zlajt zyTV;;(tA!qB)+EPXEAAjN*;A9ew;jGnK5u%;|enuK_Ry{B{wFLFJ{I-+}`i{B(NG* zCktYkv-a}351qVUT6B23+$i7J95DH*K7wi; zP3OqEE7=$ABDr~onC;-ZZiLqgDw5l^kASH7UZW@*@IwIaxXjj}2ad zAgGP$DL2AwR%$O7D&*GbN7D(ovx2SOdg@`j-X+byqA9gP<~O90z@-<#w#W>|0}IQbAzt0jNr`cq82AYXPC@2O!hYI^>nFzID{HQdYif zdzket$AUb+djCKETP`X5yO@rTarOzvnEs`?n2wpE#{PqD+$+|<=Gwlo{-YSvajK*8 zF(IeOIe+@d#wq{&m_6e`GDIYvkM*CVTjfLCL$oCDdsQS{&+Rv{>K+NOjv`>@Tx1>bQ@PxP*L>yP?pXCSAQ@)8gJK z^0dz{ljm*^ znm%LjNq7gL^gp8l`^kbgOm;#S;ikn%ug}wdgNLOp!%bWFq@OA2&j~(^bNf86ZQb#a zr6=%jD0H_Jj$2A6;J+} z;E9*W1B&yT&BSF(V}K*&;#y^S!v7p0^r}CaPDJoZPnJ!8u;7CXUM+Zy!CCFh&nScQ zn)qmgvvWc`Zg6kcMIqW356x#2&Pm_u&>a4C!KWJh8-mX;_;kT%8T=B#=NepNQ7$m} ze4)SI;Jju&Z!-AJg5NH<)+4{;Lwapv75|ywOAY<61;5kae-wO~!T%ySduu$D|8kr& z-Mbx{!ygy?UV}d;_yY#tAoxQD-z<2y!QT*kmBIfZ_*#SWvhWM7WGM76p|6swjJy84z!AlMO zAi?>e10G60RPaiJpC~w=3(}7jyvE=O!ABW(=oSCA z;H?IqFZdLLUnlrfgD)0*y1{P~e1^gA5PYV=eC@S6U+=pwr0u6ee>J^#gaVYA?xKYi*A z!Alhg{C-(X+P6U;j7h8Gl=lQ*=lJEuAD;@orNT4TaYZ58ZSt8_<8d7~gmg20GIYhX znTRBNA;QRBgfOxU@;W>;hv8%AFm~*m;Rqf(rxwv;=Zrx3*f}Gs>q2u*s2*Aqnlq|; z=uj687SUo6fA-S$p~I?&BKj;&hBJyRPim`&j&LUL;qIx(=HnMs+igrTvaFlISb*+1N zC`90kH>|qW7jJlVtuJ0}b*(Sni0WEjyph$l2$hTColsrtiw8cVm^-j>rGqeC>4sO2 zaHXrQ9^pziqI!fY-N@<@u5>3Xs2N9j^>BSiwK+m#46gUu z46gktw(mTkcA;_jk9RNb$PmOqoIDi&4M7}=tKG1j;MO#i2P|`G0P3&Hr&~ zKe$g!^FK}SeFWG1To9n2hbDNaAkL-Vic>iEv4OTVY|lW?Nx{w;u$ zxAr6YkTDMBulZn7(C+HhORQW^650V^2r!n z`TWY@Rl@&ugDd|YgDd~{3?30ay#`nQ{iSJF`P2&i*9@-do@H=N*MB1?CudFfTZUfK zU0`rcH)HSy$%G?CTJQA+pDBFC7<{_mO$OI`pJZ^Y_p=Rtukh&8vx`!g>GaO$Dz+b)Bb3!gG}xNxW(6dz*n3Qraq zXK&Fc1E1gJ+9DBS2^Ef@G42y##o&x_!>iBEBFS3w+p_-;0=PmXYhG~e`0Wze+gd<;ZS{8_4RXuuM++b8~h=`*9Y+Nz;rygC4d(J zSNeY#{9fVnsljg%+{Sk87W|YzOjGjL{3i^q^eqN27e3PsuI1I3uUd~v|D!zge=xY_ z=f4fEa(Fg?2j%v+03MXvKMj7b~03NLOivxJD-oIn;dxg(JgWn=}m%)|(R)cH3+nBFP|0hGgMEHMf@ackM zL$f-j=@#_*BHD-=+g#|2!5-;&F3aVujP8v;F|w`8eHXktSrn>{)&$xaKEra4qjS27gH8mdb}g%)brm2@FLLOBJ}qeT=_g`aMjz#46gJ~8+?iI-(Ya1-)8WoLVwf&{zT=h?d<6W zFBkfY^59n)yh7-IZgAyupTU*>5rapB&jy35KK#|-EkfUG@F{}#mkelmy9KW{c$MIF z23Pt$;1S{Tu)&qjYJ)4Erwy)rwisOXx#FNb%d7f4$l%i@KgSzHTXl4&tK-j z|77rcg?>!{5BjU819%Z=ZxQ;J4X%8)82omj-)3;7|H$A=gg$hzKT$a={Xl~+75bwM zuJp$m{7#`CVQ{4%ZE&5p{E5Nm37=I4FBg1M9{fXtR|x%q^1%)*ukty};7VU>@QCm^ z+u+LQe1j{WOAM}jIt{LN^svE||7wFP|ECSE{5Kg~`Txt{wNkF}vi@G>qxO|Fc#F_q zWbk&uzh&_0g3mSh6v3}Hc!S_K7`$8XC3)~)8+?_}-(zr<=Ys}Ud9E?ImiHNhYyMw0 zxXS-EgR30gHn`Ty4uh-w^&>D^FSSyx{UyVStNaf$c!SU%Yw&r3r}E&p8eI7=F}UXQ z7Y5hz{>I=_B;7w6T;=?L!L=SAH~786XCJqzCf7gI^>jxC@C0aeUal^H7XerLGYp=P zbsl zHweDM;4#79F!)oVhr12FUho6Cz#WH{_f>xxsy6tWf}dvacLbkm@DBy=F!*PJ-)8W3 z$^S15UL^Rv23PuR2G{a_U~nz(E`w`%izTQFo9=>bvh{*pVgR7o@X7F;MFFZ2j4wa|c(E$dZ zDfFWR-xp8u{rf2YcxYlC`fnLLA$+bhxbp8bxcbAJ46gJ)GEAH8`onh&uJj)me0qWB-~TB8YwP7GgKIsGG`QCLID@O6oMZ4R zN%tays~%nvz!S)twu9*a&UR4s`IiP)dw^%5PgKN3k4X)+7(%@QO*BHD+(!IgpDuJ$ z_@lv9o@)%Qda};oD(6iGSN(a@;41%546gb!EwX3*Dn7&D%KtKhYd)_qxR&=SgR49j z8C>ftZE&rx?-^X>ztZ3{rGB3b;E8}8Jr}@>fG320o59-!-~TIn%185agu#{ms|HuS zJ;C6b|Cqs*{w#wleTTs{KR+_K%HdZ5JSc~U0(ejk8w{>|-ZHqh7rP9uaya;yJ>{n5 zI>F$Y|C0@_`p{@_<=$;F_N+4X%8yF}UV4WpK^s9R}BQyA7`NYYeXZ z-!r(%zn?6^>qDKze{C1S0X$fbhZtP>R2f|BvEJZHKgQrKVi(^rxaNO>!L_{C8C?Cq z%?585{`cg;mm6H`@l}IsJ$__x_49oO?WvzyU!?|D{s$Xe`BxfTf4q89@MvO23J1s8(j5mx51UZXz-r( z(jxlM-{4Arq`_N-K4x&0!(@Y(2>oRSS9xA(aBbJR46b^z%;2ggD-5pn{;I*>^u-Tt zGkCk?Gj!~p@=<(0gKPaBXmHKvVFuTH4mP;Tr^eta&rt@~a-CvumFGBvYk9wBaFz2< z^WeWUxbnZ-;F{0-4X)*S#NaBoEe2P8D;ScKf6y-W4&Xt%*x%sFXQ08=E{-y|(hoLx zi|9kG!Il0*gR5P9&EQHu#o$wf{{n-T2%a{$%K0vXYrXu*;99?{3|=MtHyd2__G5#q z-j-D5>V@)e7d}TBT=nxrgDZW);HsbJ8~h!gTxhnzRe!!~@TY`+p}{r(HyB*ye6zt- z&Ob7^mg~O^uJXUf;99P~7+mXRjltiM{I55-*4J^zc>?xND1XIk4X*s_4X*hdV{k2R zlfhL!lMJr%pKb7&q7OF*@C5Ry{ixdlIP;$n`kxzI`P^l2wcq;;G`P~g zY;d*THw>=yTMe%E`>DZ|ey?g25{K58&Yui4c!}imWP@wHG#Xs%@dATuy?@K#Rl@&9 zgVzea)ZkC~Y={1A@OGhp#^7pSZy8+acNkplD15w6NadsUa*V;%E>1T1hmy}`gKPfJ zFu3OPY=f&lPdB*M%f$xQdTBSfmg`D`Yke&;xR&=OgKItBVQ`hhZw;>Xd%wX|J}V8b z^**R(Px&i;yup<}wuZYy>r3-_lEJmSF@vkz#v5Ga{B?t8>&4(RMGxBzzCiF_8+?)A zj~M($!Cy4E#(Vgy!RHD6KMbz)?;Bj{3x@6~H>E$+;7WhI!8QLU8C>blF}Rk?r|QF; zu+ARb&m+ZhgT*2KKz|RE8hn%hvRoph^iyPgWTm0sN7h%#up>)9R~U$RvUo}|qVw*` z|5p*uc(mbvoy>#84gQ*p=O-C_nPjBZ;7?1xbE?756+b@1;0;H5pwi%S8JcSFbu0*u zrS5M|{u)1HgTXa^#swE%I(^oKSInut?D$F^Lx8r!M`AMvXiqUmHp8@t^`IqbaZGx#2|^DiRg`scY=YBEy=(N z(K9rds(kvTDfQuGjR=X@jf;z+J*P7+@znRj=Paf!#qn{$^{|!-=;#)QG8R? z2a-&eF-qqw2Bo|PeSkn9%k%+pf5lwI*EG7!No>hAg}jQT%W@Ra-X|J6pO;9&;jUxA zEM4#j1<<>8;m(5a#OAm<^XLoqf`(O~iJ-&QPpJ*CiBuNx>`|zxVHNDUHvsfCR zU~~%XpQ?Ayh8N%Eo{XkzuZ<^P@}z5uzE8d}9}lxBxdL~ujuzG~s2@RmUU9E`cH5tE zi?QZ&5!(^pmp)1>xh}bGUZD;cM;#7kqW5liV89_^zhpES6dq zEi5X{%Dx%4t05?on7fA2{UcQ~(zP`fO-vSnOE3Ue_Cyf)wzP*IJW<=A&IzMi2_nGZoQGaHM zf23ok%isL7_!WS;3r7{SPeMs01hRyNO*5o%+Xl+RRi_V2jmo-%ijK;1Z}TZ2cYAg* z3bptK1k7LK%uqv^M$cX8lTRd{M-1^>IzRS>3wNCk6H5=Jln%gIs;r0Ki$}dUFO78E zZ}{3}DAWH#+`GU>RbBhz6EZ^7lnFX&v{7?)tU*#G5H(|>X2=XV0~17n3N0#nz(Pfh z5ESbqfJrFF!vtDUX~mXa?X9=9t+m?vK;@wXe4(~JY4KTgM6Hi2qE+Yj{qDWjWY{vl zd++D}|J^$u$T{bG_E~%Fwbx#I?Ke=B3r6J<-huk~1aN^9F3onhnyzS3wjJN;m@{Ka zH1pXMiMmoI%N_T9e0)81xBj_=7ye^PtAb$yXM@%A?6L}F znp?c^^^SWYxxyCh!)l-F4|1=kz+%PdqU@27e!@Qx3KLq9Mp6e7$E}tkMNT6V<1*pv_yv@4SnsX{ulV%`;_@Ol)MaT_3FV0rp;#?-sM>t77xV3~w<`U+L@C9O9DJZH1mQJ!G~f%i|> z*TCYR{FuLcP7fQv-h;Ltc$Im_%W9>ZY7f}SLo3G(tbKvlABE1d@@LRnVF+5@l$@x zBl%wNHeg1?xEuI2+Zk$Jk=MfCIe4%!zL)P=ZVG>P*kO2S%bwvoO#BxXevEtjdp_H; z<0sYo@h_@-L%baKN8!Jn{(XV%E&kc6mIwsy$NR#c9e?4w!h44Mf4PS$)1&rUG?9u9 zaLEyINvB*n6_>badgR|zCd5S_B>XoFUX3e%LZ2=^!$%Z4fU_%tc#VaRGC0c_e?sRZ z+%vqiT?9YH;G#Ezk1==yuKWo;9`~fvq|gEUOoKOD_}K=JTe#NaukOX_n($H%CEkk- zKG~vkg~6v9T;#dL;4>`TH~4G||B=Dl4KDHi*x(%&&d0s&d8_fg7v{a~op_6)`&Hxl z?*^Cjs7L(yt-(dF1n0Fhz|ytnkCk-c9*Oz-A>T-I0~gMj%iRsJ-S`FA;E)&WG8mYN zEe_{khr{n-gTsrkzu{bLZ+IzoH@uKvVuQnr)o0k_upL_)ViQ2@Yd9)!>80G=aQ=L5 zZFuS2nR91d!o3aW&vP%nbS5`9Jip`8xwGbRcf)z+4tok>n?7uAc*!N-=iY|+svSE5 za(hGU&Nq^O)ScR=??TnEWC~dx`J*jjUWs0tDewyCv`y)=Reo1N`02RkZ>GNF>4<(^ zY2hjJ`~wS@{Gp!kC;W&W>3kf(rCi>tgXhD~HP6pkxX}5?!lhh(Vc}9PhZw^t{0RTt zOO`*ug%0+Js+O1izsO{tF8iK7VK767QcZT=;*P6J<) zccC-10H-WP&PQ0d=t;!FCEj`q7dod}xX?M*!iCPo7EWIITW;Z!@2f1lTn7*QtA&RR z{_hrEZSXrRT;%hhg-g5-Te#%o;}$ObJa6Gb{}l@tI`3O}v*GhI3l}@Hk711Y%iCHL z{%b|>gDpI6!jCP2r!2hLgr8*LRR%xb!iAqX7A|x;EIeZ9EH8rp$igMwpIdm`(7DaR zs}263g^x4%a~7U5_&XLZe$WZV1)=;4?eMn>aDG~8=*+Tk;eTEcyt4?dJ5mPhr0`j7 z;-PspCP5){I_Ax~kRF5Gx6FRzz4R@geB!8))#~?O?^|wXuZpm?mqmK z+OLx2PYR~|J0t5!0Ri5}Rd+fyPHI?m{Dmv^>1B@lX>Nn#cHAG(hZ*toxW@4f?7_mB zkhlyhKe_8KF~29W5(Lmg6HfWdBh}y};p2EV^ib*uRz={rD-L!eT*`Zs-P;p+V%^9T zj?XSjfx=q6(I`}z6{p zHm-|o;nn>xw=w#N(;xf>5(PzaRXe^q-OFQ~OQ?zaRBI-Cn`&B=T5#+HUf3*y?M(Hc-V zZSIy>Zv8m7BLh8Bs;l*qrI;V!L|7E!P{qEGI8Gazs+#{4 zD2iu3hY$OE*MlFES7)LWnxZ4NK&$vT=sRhua2$$KH=*vwAavr#Fc&FkZ4~cRMv=LC z6yK^GJ(dQQu%&R%8I6;_&cnj>%pu8 zDh^5(>!0q1(vHFXs`@6xR3Zr#U|%Wg{9{x8EjrDxTvZX^D$VmltQAQh);}13F)DGw zQw+Q=ANY_wjS5z+I&1<#IZ8Lae88ZO46XPB4udsDow9xsVQ8A3$CW1FWp!Pn3M&TZ zVDud~eU})0o^%;+oHP=A*PepI0BfUEqFUCz!)hD5ewm%3sJl>fl{N83w_#C3{XU5x~Hx`V3||!e?a&QP9;jI|U<7AguC5 zVwVUcLLG&QZ6Kbz$={x|zJcMMLgk#2g>sy!4uMx{N}W@}%Kj^a$B-&oj>B>6_smBa zKy!i{Rc5l)2pOoZJ}WV4;VHOI>X_AjY9M*mSU#ji@h@Iosh>^_R8Kz3nRMl;fn(+$ z6Fq+PtUWIQ!lUQT+!NjNi2{OzJ7�zhlnjv#Q~9&bee3PvNV^kJJ|`1Hn)OV_MQi zv&XX7#u5LRUo0}+bcN?3F5gEFXvNiuhVh{*OL(dwL*w^9Ii`hyFZAc-hq%-u4=ns& z81bq`(pmmR47gRlW^)xen#X)!yF3>g>$=?x9<4TG7F03Dqsj@cm4?7K3{Dj<{H_0L zH>-Nh@>cj`n~^k&eLuA@unAiT$ygWr^b3Cye`_I#d!~Uuxi*`7`};DJZu@&lzkGj& z`QC^NPx?2}d|x4exytu)Js&t}!AR}#n_<5H&(c2~U)eGxAxBjc1Np@KW1JGNf8eDXKg25+SI3NG}V^4c4 z38W*bF_D6hT z5`$tqkSogb!A4@N45MKKLsvLm%2o9DJZB0gPVrPJefHGF3+4vqx6hk%NryUm>f-i! z>bT!o;FmuZbLxcX$2@}g+4$8O{t8|=7R2!}>AP(*1)g+RR|;;ArHGy5Ie7d@y!31M zyUxOe&$UJH+l%0Gew$7I2`jwByWPSi-nWY2pB2G}F+%(#UP*7^c~F$U;71n;Kf=O= z&&d`ZSFxd8Q-E{&h{*q%0=zKZ8!f!t(7Cq&FQoHo0Zux?kA419*wFdX3NL-J$C*lm zuSrMb{H+4KFy0FbaE6Z?`h{Z-g?d;xCQzt{_L#tKb|m3fL8ABxKl%weY~jLZO%Z%d z5!|tGk;5ztm;Ac82<}_Bc?_&7g8#G#{u>LIc<(8KZ?JIl7JuJ;Ya8nZs8LC7z?MY`HL38$5?n=2M?TS;S%qq7B2CoEnMtg zkA(}JYb{*ptg&#hKMz^Bq{}}4O7ih}E4-xZbqkm9pBKT$8`nkTUvA{%TDaK56&5c1 z-)7+w@BKyae-y#(^Pq%It#QeOPr=6)!7sLO$**fHT*~QcgR>dJHj4ayYT@QFaI=M1 zm=A6(zzf@m_ZXbRXr!L=Kl*xRjS_gyE0w6w@HTxtJI>t6fHB z3)cN$1a@y@v!g~w>qfCd?Z2_^r}-NaTOiP^Zkq!`1N-O4W-&0kGYOPZbn?ABDgKmK!RYbSv}tw znW~;|i_G8^1F#d>3A|XnTo+lXUiL&5s^?XaW$JlNWHp~LCe!Sfu%r7{Fyr7`3~*ua znPKqG;gB`fHX)7btDeZMxaQWghx~Shtc$ecs)wxll>r-=(Qn@&AQmlgFsOzjZPknc zBSIK+W5irg(&v#2S9Ruc?05#p>uO^C!9L&tJ!F=0*LxerWrDqg#$}ow<~7#cRGLfn z2i3v>^j)7qFtq&squA3Q9?T^Yy|?2*FQtj~$M<1?z`#HTlb`F?LrsmRg!-<414${a z1wOE_A?^n_RNnU)P!2w>G`vz~D}iyrL_0>R1|iZ=+zSsi!+ZmhNV@CQvaIf=l3Zx{ z*T9lrk5Nfv3qIGq{&Bx*P%Qe98GcD)>BtjU9p%UULHO8=4(g>{>3ssdxlr%)e}MpU z!NGcHTPHEMSrdz%2)cpJ`wSyVcelAqc)@jApd9-j3=(91WdGnn2(JgXCH=XLX1+m1 zsBeGBMd<@V4Ww#7LJ5DrMDNzFaa?4AeG)bdS2V6A?* zywwYr$wCo{vFm;_C{qvx7D$cRlRjCWsM1#TK+@f0L}vsYM6~@dlo()5M4vPQ?0Pt# z_@4bylQ0L@=F?PyJO5;?RqFdW?o1-6kPS(93o?UU1Q=N^_{0O#8%Xp-_V=uIsy8r@}I>BBiY(i^#|`D`+7h$w?Q)% zYuvBvY1$MPgaTRnhbDTrcg1A+5{7*p=3O(nQ9*-0Br&s$sii;2VqnTuzC2;XPq^o3 zGQW%aWdpHbNY;$S>2-8{k0FFAUwQq(5~cd%XPda& zm|CaBFZaFjQM!bu-2N6n*xkFn<4|TzvkdgP@1v0ZNr%z;z=7?FDR-MnkP%#iPkx|6p&k<}v1N#q5hM zx>zlms)JKtv$=9`q~ksr^VUP0*E()L%S{4C2syvth-4-ljQa=3a>k)r*#0T{n#fEo zNkkttI^1=u8D>Xv65b=Bz5ohR(*1xlGhi0qz-rX;dJwED-7lVr_ zj=eNCT7F}w=Q?x&0y#}-6A|DdG% znMxn3kb992x$I+Vh%_E)$IP8nrfOxEi&=Y4NA#4h zY0WY zSo|22MbuwqtLsLITp3d>Qty+uz&qG7mQ_ie;zeaG+HERCRoGSBj@uQ)BGCKblq?us zObUx&s9>|5)k=L+Zt&_>zx-Y?8T%=Yd#YxJaz=?;NQ1u^kl0+50R}Kx z&suk^AKbTfL~uWttX3~L)Ho2vb%-^N?)tT^kM)ZI>mvE0-+E6P$7T5Q@#wQUA44l1 z27C0C?#DGAeKFK`CvL>#14IDc8tuT&6suLS^d99QQP+8q6TFDi9c}H4X(54{?7ere4&%26Gb2 z#7dC#b7wwd9Dk&8TBIM0mB&j5({ifVW4SHyC>DwT8@|Sj!oSdElY%;(rr`{F6hx*!49~cSc#lJBTebH0`&|I!-HWJj15la%?fSC7mymVNi@xaiE z4QR5P5~cKFj2G_HJQ%lNAg_8+<83su?V5p1Qo3dsMjkn^U1P9191G7A{`6j`@Agn% zko1);rDM|(X>N1F%V4&z2OFk1<<{%n8+5L9{nqd-<^cJQIkA{Es3*y=Sd9ob#Jq5m z)J#fg21;NKz6hkC&{*_QU2sAxF0N1-rUasyMy`H{*i2%Kx`+H z!-DemC=D0uYJ^($Jk&L`^f^3Nzk) zQL@i_N*CEg^aZ3~QCi9YuHPgxnrm&$;NziKj`hQS(tQMV1WIQh7JWaIIT6F=T33~rRc${yU$r2gZpD# z1^V-iO1X`}j(d;LH&NMUL=lx%OsI!yNG(w92^9tzU(g6q+ggPBW+IsIr!^PeNX(zy zOIM`t7wD3TWiBg`HjHtv8tb~A)-ke$N9~Jwo7LpB#PA&tP$}xxC*5bwgga+Re>1#q zQ>p9l>OtZ)a_M;p9DbGMn12A;rYGjx1L($)%9;~=GYd;l>6RK_wt-3(9*TLV!@{Ai zM^V@ZEJdhqD0P2erkyH_w4X{m%Aiv@-==ra?tr$p0kumX-4>>iO<}EDsZ8*GrgD6y zevsoHoO0{0F68;F*Ii5LNnfZ=q@HH9%T3h1&sCel~ znAkXtWn5))EcZkr`r)E+N$-8fd)CZqOuApjGGj{|H+&z`5&yze75>mzX<1t)jOnp@ zpAp#dic@l1qg$Y*(|6OdpVGB1ff^54~Ye>RBI??-jSEI;jpuZu> zZ8lPO!Ggj^UV~Ig4_6}7USd)nhiW|OV6&dG?#@84;{a#LL+lVNSWLh!Hzm#cFS&5m z`Sa&oFemxo+&LXrR?nQ(k-T@}yg3)2Keu{L%Da|2lk$Ge#daz0zKOW>cTdINS#HOy z3;VmL<8~%G*IxQc6j?+FJ?hYlDAwZPUeq~A>P+;B!Aexq!qQyKz|Chde`sz)%tNQr z(0Hkme2UFPrDZzbTfOo%BPxvTfQ7%?sA3!3;0>>qGUuxf=4{d+rp8YB2osj4>;~mG zFjx5)vVu(cIeYkEp+CR;Kq^;RtbY(Yd-FQIF0vSpZSKqTBG4{!E~Odva5 zxfv>Kb|&uG4y#F0)$n`&bd-CO=9CwNS5mf@g0E{V3cP`cqXMxP9=7*YmP;XR%7w&)}&)*Q4K;g>NT z_5CP^TBb3-ELOT7z-cfCxvjX-)8bXR)m44hy~@W#cO}0)mC1{PWh}_4d5t<;f`>QM*4Aozj*1svD{X4XDn(}20o~vd``AZ4!$;61DhZfYe=&&8*b^J`4DJi$yZ^@OzM^c~W ztND#>F1#^?;j61#O6z-aPhbP2P~RoUzBczMQ*Ux7sDauIDz9tjP+v@IyDDymxM{7h zUW3xW-F;+?U*4B;O-Ch~E4@erHVmuZPc>J{(Ogjl4yAZm%G;(o=$}Q1xIdUx*`H&X z<`O7{=yABb^k9_Db0@_`Hj20-bbxdl<4{FDdhyPOh<1!Wr)Bb>+Kx#f!)v?w1 zz*-aSed(f<$V|e{W3oYD*LC>@FuKH~@4zo#obbxw6DUQ}<3y^Bxr4kZA?xx@dso;% z@xs41+0)V=xJ=-Vj*%<2uZVJsi8OiCz5Clc7U zjU^GC3P!Z1s%K5rcNE$o#_AaMHNWxbmX4w5)<+MPbfD|{)!m9wz-^2_`^HDC>s9iU zBEoid=bc$qw05py%dhutlqE`jx^6ouDba$k#;SQ5f2KUjt>FI5UEm%GE%gxG(9so( z)Hc~mNyylU>LH2Ycs_6 z9>sTDcJ;f`O-=6x9nVjTqlxNnB^$)`i?csKI{Il~1KEGg;+A*f#AYu8Li3M4`uf4j zc|m_CI*!YKpZ()o49pL8&KTF~SqGk7DpOt&^P{HM!7mTTO7}$zYFlWo!2L)y1v0NAJ`ax*b-;uW^)AK$02%GQG z&xg}RvKzaR_Fc`0bd8h4dNs8$7vljjFDN@6%D9?8`G=olqeF~>sq8|_HRi|f`5a~X zu)G(9Me+_?wB`4hP&zF6#HjE46n}Hfi{J6N5H*8!Mie4JxD;x!HpW_1v4>xAO-pI{ z^4!)~6oXZpSPZlcKNai;vNyj$9|r7mBm){U5kg`EU`6(A1l8h~Y{*XiJFU!C4AuB? z?=X{gZBD)L9}Elb6RAx6aWgnajjloSA-8p02A!Iw6=A9?=>D;EA*yks3=y>T$n3kX zP+{Qx4|tChLIdnCnzc%R31nJJCR~C6=X_O(?s28OSoMxt9oTE7#zB& z^}?0L_oPP59`82&5Pje4jN9RUg05iHGbNZQ&{NX!O+$^+UnuTTOJmcrE}6?GQT&{y(~VIMN_FOUz-)&8E(w(J;m{c!!k45Jt{;nnzWr=L?j zZQTJBs5bh0A0G;ScKije_PAxZ|Ceh8IY*ak?c^tSlqYd{mMim{xTIfjSu05W;7@Q} zE(iAU6r5rq9hqAzIP;mf=#}7&1{a$wIOjDod^N883EqNx;t_=o;H?I)vGA0^Yc2dt zgO4=0r2AV2Z?N$54Bl+vvkmSTT==}y;EbO?!7s->`JbrJ0ld@TlP$d0;8QJ}kN^Lz zb)=T>`OBzB^vqd5cD%7R5P228-rL&98xWvyP2&cWaX$xc+dk6zRT2D-B6z?|u66_1 z9PB+^Z8$*b|_ESM2f`-E(!LW{fKt zXSdIv*Ri*Sj7ZZoV=!o=s3W3Bvn*Wn=TZxoa(ShNOZoeyg-iK+un0cL7)#+t^2lBb zD0KeC3NQG{7B2iuvTzAMzX*P%g&Xw=thI0{PrtQrDNhesxY!$ezeS<*cPo4i@`k^6 zEnLFeYX>FX&#my1-okwwnYTi}!c;c=jJSj!UIdR8!OyU8N$)fZmwcIT;S%r7Metu2 z!T)IC)kp(>>nvR2{j-Hjyjcs6Ycc_Q?W2VM8ij?Q$W8S2XbYEk8!TMtTxQ{tzl$wg z^7ncR7dhMe5(=F^S>Yw#twr#cEnN8j$ijur*Y?>{4uT(41h27hp|8792IMJpzGH-R(Oe*gJp$s6MTt<3!R@@xcDO*EnM{TaSInc-)`X&{uK*v*6am# zTDZ{p*uq6VgG?hs@}=6)+0Viye3OMs__&3~4V{#QOZabFxX`!PJ_?yE3m1Ku zZQ+vdms_~Vr_;h~44)Yb7k+NCa0&kl3zzWgE!>#Rz>5|x;qA4O!spvoc+rP)<2sA{ z1utC7$T-dCfqy9yzShDe{K*zB{9ITB&scbkk>^cC@LyYag$aL$g$qAhEnMvO3l=VR z>762Ygbh^uL~atkz6gF+0sb%ePV`^)OcFY>7s4e4;U&)*-?bJlbZ#z!KVjjL-j^&~ z_#a~S$Q6DBuP%bu6v0PZxa3RJ!iE3SExekE#c!O2OFo`y;W{+hBNi_F&$4id_i785 z@HbkxV2+Y_xDGr+>C^u`}B(T*7~B;Zlyiuy6@Kq+ByB`6zhE!iCP^ z7B2iBZQ&xf;TA6ZpJ3q?jTX=>3Jn&5m7d}t2a4GNc z0=!Ue;|lOXxm|4G!v7T(F7f`+!s`v6TP(cV;7?n)gnz-ph5uJAT;l!E!iCOf1$be4 zrPEU6FLVYQ!3r*Xj3R)f?r_aLT9dpOS z6ySya)y4vx{8!^YfA3m2-|_b~Zc2)u$W8b^&BBGBGc8=o>4g?9;X8}qeHJcsesAH` zin~DIVG9>NUnsx}uN@hmSa zCBKCK;TB$N(lye;g`blwT=;LbaG^iJ!X^CK7B2L^YvIDr_bpuLtS*B8ssJz4=Q|4U zLcO}X058<5CoEj}dCkJb4t#Fmk}rp0BL)6M{(_%a1aGr&iFaxd{GuZGk1br}_InE# zdw#ctYpw%<2Q0k8ym-vQh5m~Lc%l41D!?f-NtYNFkx$&vKiCiyT;w*Y2;No%Ki|S7 z-Z@3^?-#+BTe!&KR~9b(KV;#;|BfQ~5K~Fp=^bj}LVvV{3;i)g@T7$coo`vV(3x-H zQjd39xP-sP!fQ-Et}eg}%iYfk@F2ogoA3` z(lyh7B1nNEL`GES-9lmBnub0U0~r7 zevXAp_)9HZ;$39nLT81AH<|QaZ{Y?G+-l(>=ie2FP=UZVEnMU<$-;%7X%;T>Ki|TI&LtLJYa;%sg$tj*v~Z)| zf!|uVgx^>M|I)&RpRaS`EPf)NpneP-YvGbFqb*$Ie7c28zKpYQ;j`Vsg`ev!T;#mQ z!bQ%vSh&#ny@iXMcUZXa^QMK1oZqu>2|uV>3rgfB_^B2y{G4Us5&e1Kf+DzQ;ZnZt zvT(_-CoJ4N2Hq%we`Mj3U!PjI@Ocmiv+-(}$v@0S)X^oN=PDETG$p%yNDHdwgmL!t;i z-ok~S$rdj9@Er>m`U{HSODtUU|3^jem0>Mdrk5fS|5MUk0*vqEck%fhIBjSzd$iZ@ zeUJ9hCyr`R%Mt$@d$i9mb5a>+vx>MGr)TerJ=&ArCj+~M$YI)lnc{elPx7z8$+4Tb zU-)jW3~k`bcWifp&GUM9bsg)6?qy0c!C~>tStVG4jRSG9zfFH|J?VG7X%=I~{3$`b z?lsmpr8cx;D_)uvx&sSq9qfVn2{xU?&a2q8PxYH};bytn0JVHbs^n$8Y_>6fR&Hp; z{fIy5Z8B?3vA7p2O@r4unaKkSd@Bya+UwF-`v14>o)gAwI`QsoS>OXAPHE|J}mM)w&=hl$e7<5G)u!9I~x`?V=L5CnR+fX z$L2WCB{JVF8SmC#Z;m463B!rTS?Zwh+Bz)3#l{lTYH{@K)ZyS~c-IE5eBK@R&kL)q zBAy1Ngg;9TGR2pW-~9k(1uSBjiUU#;9?lvs|D)rYO|P-x&KBLC&&D=f&ixl_swBHmg(=uqSzc{*vVZtCo@L**X^-P3L=!<%tL+CmC`LJWPVrI ziTAJ|Qh+NRH;b4z{Jk{#0jN||osi5_@!;lZRnV}hUq^&r@7k^zD#(XGe$AYHPHH^} zi#^3{K+eI!n&lOP&KO!bW@z=8p*4D)a(w8>rGw)`8@e%HnBR$A<#(5pL;MQ9g9p5@($~WhCobO%~INrVV zVxB9jIsX6lw;G=_>1OJAo>;TF8yw6->PCDALD?l`1yQdW%p6czL&`_SQ>NYyj17Ln z;H3tai=3w=&vLcnVqHg?#lAOHpnRT>Ux1TvL%s^@JHC_nm+_(CC;SUkhZ~zGzFTeP zj*T<{nSPdd`Cfd9W?*LeI_?I3PwtHaK~o=3 zEBqMu_V;|YWyeoun1u3R5&k%pl+%Xn^m7XI-s0bF=0-Q-ec{iJzwlk*J;VJ^t|69m zacUaZu*$Ps!v>e~BiTzmV0gagPjK2a;-V*lR~uYxp5PIK^F4op^S=06*u7~U!wc8^ zTK{TrDO{^6c6OA(R~jV{JBsrzmDA{A(dfv)e6A41qS8@VR5}`qO6zfdBJObRmgrjryYo&9<%gys_3m17Ba{2IrFS5d$$H4U#F7$t6;gXMk zvT*UGH(R)bf3XPufrSg5{f)wl93)>4EP_Xh;3F(tW zW?o775f(1x_pBngeIBNS|CJS9=-+GM!p|obF5#=e8-EnHNs4-&s{Rh(Qm!wa)iG!O zKohXKu5M(s{>1v|=(@eP0qaJN8Z}xS)HP$jMTykdK_w<*Rh*}(cuiFK%ln58glSf2 zGi**Me@<7M_ZZylFDB8+Uh+-@*zS)<;tYsA<9SZjNS+^6<9I0?C*|K3X-5d2n6(hs zP|tT!qdD%RYQMC1y`#P5Q1AW#L1Z?igzH=~fGfY`btW!>e!VTNdeswI41}x8fcD^) zD0Xt=EjMWYbr6sE4&SD6OByp~;`;9l7wWwnSSpi_%;K-t`_QJXROQ_x)6;CMSyUXCYtVIT5o%J=v% z^z99r@H%xC8220H@mvZ+_#b})KGZR=p!zbtItFyn1g-rX?dc9s(;qKaAEPN#yGzRf z2V~5Ecs?@Qn5NJGh_`v~r@Xf{6GC4o#IXhCVo+AwFQ>r(5;_By#zY{roaVL;Z5W(J zQny}xS+}*ZEzo%&cF#J)#rA?NUU^S$1EBP~l&g~Cg0T?af|I#VTXn4a^b)mQGu5G> z#lQwG1O%OE^WK6iQ{F3z{La4!UppVv2?SNNJbEHqzzUil`ex@%I0Pr3rztml1kOIGYW1dH7f8R+*ctFX?W|Nmv1#cz zH@r0FrLGH@6k(Ujy7h=f$Fb`xaU7{W#6DS|&uw3$pJLy-Be>lwPRHs?zp2QFGWVf% zYPeBtREOcQq3%y{(9HwXFN*K&>?#B^d59Ah_=JqV7;W`cDnHN&JMKfM!8aiX?)m)j z{F!xIj&rO281vFMVed`6OYg+C@c2IcNZr#;2AgnE1stOS+1=PB z@&B%0*&7jLATjrVWxK%S`n5cz9HDGD3gLcZ;Ftx-3nCk_qZta3Dn2_{f+p(krUbA@ zJQWpEdJ+HoAsf|G0NHGsKO&w9o*u()l$l#lRd=t`#vs&tJ)Vqdpbg0`#q*v?%q@>B z!y6Szb_RpTBdXSNa8rgi0c=(o;gyWmkkOH11i+`NP#=Kh;2z?d$k#zc-Jz+z%INX* zC!x#wA-ft|J1VOqst=MgvsVHwFk;yRp5y*^(3yjCpyK|dvN(+C+_*m;d#+-Wxwzj_ z5r=eU`d5W<{NXY%;Loqb0fvitH@?bSu0)Xi2M-D8G|5|z2lko7zLoTzH9aNTihn%G zdlW|eE!u-FY;S&f^+%y$@kp4*0G6r5pra>J>Gf~;$B~)(Ay0kjec&j2NPTvW<|gU; zK0%vbIRfVf;-e~bnN)S}E)DhkD`(g2F@(8@d4u279b{RwDHbg&|;5Mzm_JsGPU!^#!9q&CS zvr3-~>3y2={$co@;y9TFWp&sz`X5H49d|A=u~8MRP~W}a2I|e!A}7k)yjQ#zQr?Ft z?@OVPa(mRlk}18_K-b{9tvKvw`Uo6Wq&`7tCv&HX`5%gaiCeQHFTq3iM#t&iT;^of zso=uUl7}ez0)t7~nkkUmOC;V4Du$g8t9JzqBe;5#%$)5cGglzpP%|mXqmf&hDugAe z%YGNO=PPJzS0Y%lpkeQLsAn|3QSrb|P3>I`5#nZ;y2&0=@UG%I^)7@0fcNTQ=dbkv zfyy|lKD?N>P4^_jpZIu^)BTPU_b*gh$j)Tg1sq7J^bsZur89*Bfa36`ieE8Ur8buJ zHd9HPH@tUbrfM(}_|!kW7o7XRn(`2wqq(!@zK`-i&t_<8Gf2f13BL{7S>L}H;T(T~ zgSr)mK4N$M+NPD(zovp5m2z=_3Ur4( z-W3zv;ELR)=%YUF>X){7lkW~m2XYld&TiK;@hORS-sbmt^sibY0yU+H9%#t-pS}< zfkL5zHcpQOJ6%%~ncCBw?#_n5f^*1WwTb9cMvdemHxOTZcvcZXIdc$a zzMQqqd7ZrGHno<{{YC|&NdId}&gJTU$SKfwosEiW9EDdAW_%!Rgre*Goxg_t!Wcwe zU%sHeG;}YDz~zJlm73IsdiI04_gib?{v{RK+3TqS5?k`cn{ehreLHEC;Pmxu1Aj`o zaqk}q?;Vv4|C|V=Uri74S9ss%e%zM1v<#c}--Ra_dRRimZ>`ES7z&YM%x|3;LQv#h8P@|sZ`@s7r$!;y)2#1e2NP~8~JJx z==5uw96L95o{_@kN(vR06tb7GN^)_KElYY?_DZpNI=38<{EimuIkD-nbMo|{8{5#$ zk$nlSj5bglV4!_cg9;z3L4{`~Io>~^a1~0=%KfnwapYrp_wHQA84{YXVZ-jy?%gxJ zA)&rcA;j*{D^h|=E=%UKKXa<6!jKbYO z*@ODvGi8aOVJZKrg^vI0#UQF!Pt-jfZ=B4~!3g}TTY>Y3+gtP&^iMJ`gwK|1ks~0n*e?>FXKGE^d zhT%tvrO@D4o!tOhWSS>9qimevkSJu?jHsAeB@mY18h?Cy9d_29R~g;LQ?HqWDgWDu zVvTYoQ~tPS*0NJm{+N-hb0N}s5VAV=@+^n+ozBxtDZ$BTbjvCyxEvzdqvuBBtqrEScb^UT=>@U+g>*N3S`4I06!FnOYA}o14IC zJWW?8yv{)Sm1ORr+~Zf?$?gOuROv4FyRP8@Neyvt0tCD!!f4{&xnblnvoGd-uL3A_ zG3I?c9NPuYq+~%gbQldk6l1NROCH*S0AlB2=WQ~28)t9I)WwVrttoZg`4A4g$n~QY z@Z;P&Db)Z|OhzBc_1j(jeS<@T-H#Q;#Lm_JOFj-N031P|ctLgV#{E)keUE|od;F_{@!|c7MSpbT{9xzF4w@Ly zklBvAL&<@uuHYfPk)QDVtyZu0SR8kHH0*!)=veOIc*!%3mj%<0IglBgA)PN?HtxNR zDCcZ{9{f0^Ya)wz^>(O;kS)#Z6+z9$Z1yj5P{mcI{PESwNp<|I&;)Qt;+RC7uroJO z3FdKH0tmpERKy!62B{gyJv0zP8QS5x?b6XQ8wdE1DsnWD&-ofJO+oj^1Ei(MVv$PHbUPzsAFGrspU4HDE3h6)7w3qhKp$} zD0qq_KS0k(lX~#r)x-a#MRq8QO2`J=^W&(HjR~)+AvU7?^psx}@ybubrub!ExH0Me zE#}q!EYUbA7+T&8&w{jTwDHnzHu?#&okyZPqJNCJSdrU+lOpbnW|QtI3BT!{gm+5% zbw*g`%vrAl4dp6xaLUwuCWEKCFFEYxKIABi$6r8J7WE<)Ol_b|m?Iwe^i1?d!7^%=HO^KZ33XgaJQ1BW1Ia7oJ&4Ak~RU+W@I!E zK&0AtP52kKt7$)MsG3fLc=WZ-I@M@r(Li`-0(-YXrUPeXErIP!-4Ju~;xA9W1Ris@lm^{hq!V+Q=;KnF0%k z7DK4#K76KBmBwdA%6%(UiZ5}R*l!pO?FniYZRc?|#i^KvG%{9N*V0&jSZKu}Mu~_} zc2N)+whZiJ&Q>^zIYlzY`lN*AaCy=+1vD{;Anex+C zX4x3?>u{XPgR%Y+%AD-Xo{$OOipXP)-wuW{8;}-dU{dZT#W5XaGNQPiIL5CXg2O0E z8842ndK}5msN`qLqe#tZZ5h}D{{Y0|ZTJMIxxokye>Txrio$k!D6yerW6ZeQ=6q=R2`IU7C=Mj5jd;Sluw9fh;dM<_>d4Y0 z0rn1{x?=e)sIHK}j##ub)O!VDrBG(XX&@8Ps)o=C7Z^JmwI-QykZc=Jl_+u_>OGC@ zLNz)P(fvccG%i$+86Z^|iv}A*D-H(~8?oP439-q>Id7jMb<8T&yr_oQyxJcoyy{r) zq3)*B5W`>bKF{YiJg5kmH{g>oa0~<yhr~uq-UmZ%h2Jey)=$s*%eNo3@r$Dwp7JlBk@C-7==c***WDRe452!-dD_0Q z6fR_cISS{us#AU!qWUc@O3J?wwoU2cA89j@V;F2h=PNxS*gDLZ6tl@fJcHJ+hQ`pL z350>1X?kn;p=32}V5Q1$dc+G^#8Fwp3hJ_qGjn-F(EG#DpSM2t$@5Uzc<7Avuz{bz z2BM|aOin8xkPbvSR~y3FiXP8cS`0Q}2#wx}&e34OD3->=Aa({ zsxau7>*zc#1-}`LHskf&F+Q4d#tO!wP3Q`kuFN1qrk_nAYBB+P*p7>mS+s*^0_wUn z=3hEB?$2(AfWkPl8U1eTj)9AW0Sqd1HQO&7m(pg@E064v)euL_+ZgKkTv<4rph~vN zQtobA$7+~|`xz;l8E}bU%2Ju&X?e?dbZCV>|93jIDH37-C5CAb>uiK=N34zfsCmRN zWf$usu@NK5Q|0ia?*1&-ahkH( ze(KafW9n3xNm8we16Ao>NIj(T5?uJLVr3Yy2Jz>2pXn{TswI5r&c_zJcvYmQ*-} zNYz+BvOi9i+BfO`HScL{0MDmEMyJ4l!&akNb}-E-G9)(qX&gbw4=ar!t?-8q-{1{} zKi3E@4k8zspmNw^e$(Jyl>CR3=;6tMYQP_?tnKZ<$Ul?sxX&Z`%$$)p3hM?KX0QBb zZSF9f!rAIotvt zCpAmo6ZGfCqIIF(9WZ804AdPCXFOUC6a5HH-w2FP;K08(_E7BX?^JM9@onzII1_w{ zA$b5`N(@v`|f%qEz|E$X^FvL4qI`jqa*6|KozaS1K=&~os{hW!Z@KZXIU!lVR@ z;)OyhE(6Z;O(MIR(K*agEbqyT$Zq>AnQ^hplE1|BQ)_--=JpYfkxBC~MvBATi6- z_iG}HaeWK_aiS`ck@D9vVzRjwSK4RHMz~X@MipGgpIDjl7gp1rk8JfL%N&0;2+u~S zuBmnF+x$rltP9`)qoIWQ5Ixn2x}5G>;35Z@x`|2uBKXDV8DnC!W1NV-$(af89g^-g zmRB@+`vImhwab!jXTYzzH|CuaNdJ{dr)VDtl%Zd!4g>nyRzCo3%RNXCBReWR>~BVT zP=J_<+2}2!9QjK`KZX;-U*}}Uy;I2zCc2Ucu3=uKOTU_aB}LNazC^>;-s;!?B6X+IKo8Fk76U{NkGk%BfE3mP!Kgm_kV@iy1V`=O61fczp`N8dC~S{*Z_e+)Pe%mqV)~VZ`@XrszHH}B#2xU4!L)mBcm%3k)iP`YQ?+1)Y zL7)0fWsdjRl2>ymIBl6Ass`<>{tQ(s8#duy28^Z;LaHtUh6e2morkmkaRd4@3tpar zml*$kA^rF03!$DMpEiSm^wN0aok}W>`%gXGE+Px{tV1mvM>;9A6l!DiEVD;4^gAOu z)>l*n4*2dvK5&-r&mbd8oM$xNjk+KJoBu=QIp}+CC;rKVVVgoPV`aZ zw8fT^`s*RZ>qs>(Rfrn3)qpfxOM^AS6*pk;71x}Uwx8AJ_qbc`;vC+AA z1v(B^1kt;@0nfbw4C^r)-bWa8D5}Lrm_4&kARawF)WZxzMxeuQM<)h|;WeSS=5WYg z{JOv~q#oUYMNs|0#Vq3K9VPnwQKdBC05W8`CPOn&?Kqh#rACIar29BKUYR*9{lS|_ zAzqS-RPs;Q3-&oBe{)LEn$Mo5su8%iEDR1NS7ai{i!fXUG`3Ku!~HoW<~2pYD6&XJ zG1i~{HJIKbkodBgw_mmq#F=f&5E+KTIq_+Xmp&ZAX}X3QPZGoi0M)|$`cSL4E@ zeoi2P=wYsr?_&NvTDd2v&Sz6QOLrAgNcP&$vDxO&Z-(b`t9ra>BD9c9q&TXjvnme0 zXwn={ckinDo0as!HjWgcVb{*OdB$4^1DP#sR^3x9Rn;j~D*G?^3GFNU@s`dm~~P!UG9l4Dg_OFiwl%Qa_^)k;Q=Po|0og^^aj z)(1cEEzo^PhhcVpJUkYCPdg2>lkO8Nw=e*k0j4q$I1Tj?zv>P&P$KESa%ts6RJIhr zo}*^uhQC<9T1bQ>lBmmhOq8W~1GrW&7&~N`q)I9b+866ombcMnVHg07iW^J{RlCA8 z2voCh86$!5G!;*JlbQt@hrn*Z8N-qacdld6U>2g%V*x zur}}7l)GN}2}@LD7{*gMiv&>d=q%8?S&Vz?P_vI7Fck4Vl3>@{O?ZJfXnUe=J0Ml6 zdvkI6wqLhB=6?^K!YJfJjOJ}NhDRCwR8(%PDgu5ugky@ygFi%fVxh`rh=nQlNtmSl zTT4)LplkiT^n>xnTOw;26)XC4P=869Lp`tH3F%aCS*h!qoAo@C&NjGmkMMzvJ- zXcqrScL}&}Ihp$3A-xQ(WI)SHY7`iTFng3F&|gSV=mr{@Y=&2MeQQYsN{yx*8lR@R zM+?SBZ)BKS$>Pl#QJ&#!*1CXaAJD5#qSoh~o{ik021o zdR7gsCDVJgI35_63Fe{&VL_ z-D%{$#sMS@ryPq>1Jp8cuyiEquzgt{n>=A*SO#MBTphpuho}sfXQ#5d)fF|qK2pg{ zQ#f2xxLehhx2Z4r7QL?9{M0_w;zx@ShpC;^efG0YWs;1U&%ybm zs`c6Z&TN^?F@xi0=sx3dzpyS&sCPn;yds-vCZ=+<4Xs|5hN*EhsQgPYi1F>_B=mue zLJWG(jl@l79J_Nss3z%u+f0!_yDm=dVXd1h(Oj#hg)LJyUbT)OY^ZDG8k%W%yXba8 z0}tF_d=5s}$9M-VJVu1wztHr`WZXpE`b6~Q&cl=L7E(u_#`?BQ{R&`7_cXsA?X{EA zuaV^$rmd#ui7VT0HPj|Y;-JRm0AQ#Z#FTPajgPNAJ6Q;ib8xw#^L2Zv^+8WRl#*%ML z+6?*!$D^-ye%o;$fpfOP@!nUiF6_$^zeHKJ(XeW8)j7NZPdU`X6+`f4v+c_hC#o$Hr&Me`xp{kEjaytHbkN_~Q!k0sd&4G=I0WdH-RYbXb$0 zqh)ZS<31ISqCZu&9zN}?!1yGd(VAfE;ZxOm7-rI*%Ansn5gpaxI_@WRPe(t)fF|01 zPv>x6e7@Q6nQAs@+w)pUn))yu%I$qX-9Tjw<9iqQ2`qU^QZ`n^=BTAO8cl5A6u1q`)4l#0ZjH$ z;`KTXLenFDkXmt*>(71(qZ7-;_X%X*$=~rLc1+LE&T_}$41c%^??rb$=Ac6a?!MRY zHJI7>*M!c&`LBcdyFs{f+t>mlj`}r6BAb-Op(fcmi)VT4dgwRF@icb-TJMy_sn%Aw|((Z@QdGNe;^EZKo)=Y4w4w*?$ zEac&@(BCaw#?*GeAKEEpPBq8 zTp16&pP>t!7bU2Bk0Wqdl2Az^Ejypb_$}}?oghzFO@G?lQ zO5(R6LC0-DpTs0^+lY#z8G46pBRZ}L8r9@W7b#XsI6hO`49bh4f|J){T6oi~pb0gc zG||ai0Wkhc(B*8OmIhU*nT|9gaNMiV4If_YYBnk~euZv;_SCPNoZqbK#OsLIPWmeODoY@#}-x%aJ%N zc|jGV5(lLp$9g$a|M=d-C_<^u-idtIl`Gr7+zsT5N!lyGl(4-Mhn~KH8D) zx5BY?xCXpL8C_DR`>F<1OwRyO!7zL94%}l>ZfHdhZgN{X=KBlE9>i@RKWY0$<~hbk z(b8?466pG-5V!&PM_tmt(*Uey<&?z2xQaSp84NUHT3-m_de6NpWTd!Mv<4~zFlr_Xr+^e_n> z!-$upffr-Fdtp6qH&8oQ>&pZm*T z%ZS=vmh5EE^fU0q8seGod?l!sO!@#Z_V8;|Cl$q0Nxuhw;AAUrl2cneOsI}kqM}(D z9G{u|XZ)#E29zEVygPi9^cGete^~LKgz%eDT5k>3z1x<#0O6-!gA#iM?9F#!4$ebt zsAVBRm5(Ne$RoQUDosyAD8q&nk*Q>9M#`&){ZxtV=l2zK#LL*<+qQ|1Xsj;%$;rycA_cp5fsC;AKTn5<6X2X z<9@lHbTQmn-W`p0?CZD>=N`r+*d8yc{O7U3^fOSAc;i{Y^vziHXgG&uhdf%mxp!bF z@=R(i%su)Z@!I=`nqQXmr!-*BE7loY9FFz(DxUy}ERaCwF-gCzS>*vV6dNO9UTMOg zIU<-C5gEaV;$CEU`X$m-*{D8MLU+7Y$0)@xuHA88@|u34nM-4u2Lz5BfhK0sk%?Tk zqrZe}KhWWaE*FehQOHh9rs;B}1S%FbALCwoMXO(RY@0WGWNctoTbs8KeZ?;&ys6T7 zFmpYyWGoDOTnn>ZwZ-wi1%+t3)$uS7c`Q_=3+<(IVV*ZCxj+>ZJ4#>*!S+^RO3R1_ zWup_>i2kyqpM<(Um+PnR*y_(c1oI(l55fDfUhS~-->FoPs1_-khL8zfCLx?qW*3Z) z63r)G(;d3NeUyELASlo9no3e7yOZ8yX0jtz_j((!D;RRR%|!eye*xT9_A5jX`^DdM4Of`D1#DXfouA0Ft3}2jqxGD z1=wr~gEs6~W!h5I`M6hJ3U->%G2Oirlbz7%kSzsaU0m2+_h8qs;x6g!Qeuxy;hfRQ zs0XHa&rHH3lJ0j<7cwhdte48Kr1R%u$&I{rj^>X2Br6z@M02WyBWYrD^{(ZQ`>rOZM7C(kJkaRJS1ATn6)6#m~jh6)Bwnp^cJ=xy`kRQN$?ym;hZVi z`W=wK9j)F)(<~G4&bMft^v}j8zp%nwwTS+K47N#sN=u;6V{3ZYBKk}rdgW2Eo%k_E zW?nVW4%TptO62KHNT3gT>r&|t#(7P5nnAuN#!!l=Su;T6#!WgtJM)`%fZ5Ekb`?mb z_a)Qslk>j^sd4(f{1aKk`YG9NF}!;{W8xd5@#-Fy$foXyG=2a~S};mT2Vv4wW4In@;xk3%tSBBtJs*WfvuMt33PDlqV zHa}YiyaIUeOc3b%0nW|=fFq9wq5LrIx`;z zkCllQ7hrcaufc$5J%zV9aFR&HX*2SY0bTf9V9wQzmP6gJ*sbv<5Lm6@S}!yp5q_4B zBg$IGaJVkhs5*gfClW6?GL&}SjedO_@f|JiMrUoFm@PYknt=5$xv)U*=IX^fe(i4i z8ZC!Qk7Zqn)$nHv3~PLrx}V6dv2M_k@hyIhXR}NXd@g*Z^Wm1@3AqsjUh%$!f0#ew zA&H|whif-_>j*t2OmymI0LTN#Jq9ZHP$b{$57|Sr5wlk^CW!MEE`%L2&+9XV7fI|s zD0t1o2h7DGuMsC992%hg^@*(Y$JlRjvWt$G6R~}bQzDGY6^zy}Lzyzc7jNQb+%F-( z*Y&?K!&vy^wamqw>MH$HuYW3CuNTW*n}F4@`vnKcIMJzl8lS^bS`*R^@z2p^m*Y$V zM$2eae}Q8wcD=b0UG|Vf+^x;4%xT9Lq&8!Be-_fWm&DgvrljREAt6j%%{)i-1vMwW zAG3$i<&QD^MEU`9L!CnKL^nXXdq`pSfpH5NWejV{>F5GyxKw9kb&PxKoV9O!ZhW?E z2#1|7?ssY*alNxx<%hWbu_nU#7}q1P_E|oF;;DG*azgon6fiJ<0jADow|QnW!FG44 z7xZ`dOeFW+wsYb8bV7z4dLv-H;Cp)ef#mGOh zxZ=LGZ&^#co5gzNbne*i*7hV;V^vuKcP1Y6Xs7O2$2-~|-8_S@-wseHRVoIxQoWdK zEVc>6dK2%51>J9o;=d>7;&I2@69z~SOzJjQ3@7L@>O|vvoZ_(~3~*}6Ucs&IdhsIT zO=)ie9P_`Fkc}JViXkS`Z?bsYqDdnJ26uFpu#XzoKP>LKzao)U(-pc|lCn|~BiBB^ zf4$Ru9&+=!x^3srl{oFj?371Ws7`K> zf?gUj-XD9^_`0#9fc;OTn6=d^q&)pGF`vct_baNk?j$!hlX4nfL&wQs|3uC+tE&}9 z?Co+y&^^1ii*ViOlpePPp(-Au;_NRWNa&}Y*xbr!*LOIR^GWpP)@hQU%f*~TSA2n6 zqO?-jp1IAh#v;}@Lr`wfx-iC|clvd*YED5;J_*u0)r&NuV%_Tar@8*&-TiTIxYs5!oZkplk0N7bjVv1h2wlEN1<1{iEWd8A~V#`a}BLPtgb%Mtk*w{`Ji>FNaPXjn2aOK<>F1!6Nq{ z1zK9unAd`!i#O1ehk{X--S_=E&ktJo#9{sOZ)i;)P9T3OYlDY8o_}$uO3WGz%>650 zQ#k*{2Br)_Q_;c*kgZ+spP-m=os5}aS1GkV$M;9d zxtz(R(!D%EG}Yy3b{!*?pRDI_Q2me#nRo2#i$)~P<^ITzd28Xj$_7B?)3^oW6t2B4z1Za1DOrhnA z%FQ)Da#g~cG8(nW`?VTC$8U&s?PmRJ+_bx^x`#^~Tg@ZtZk&*<{uW{Z+G5ZwABYp) z5PLI0-GgPyFvM`e3vgD*7*EE>1J6$9Sv`ovArkj4yO-xWW`!~)nu&pbuHy`B@!MS4 zcvfa3q-t&A{9S^}-yIh{Va~FKpuks7mbUuOy&FCMuLz(!sj;>Joip;e%%etYe4TG) z?kE^Tv}*(3GchWy-lYf@^Qx;_)9dM9ytq#tBjle|?y`gzZ|OiITqhA<+^D=Y{RcXS zhr{=y{=`UZZO3O!=eVB|K1?i$JOo0#$9E@skt_A#-c|~!@NN}B{QusHft_`*a!C8B z`Wf2Z5P%4SW(dd-IO7r>M@T76{{cn#N?KHF@1PMbD3A(eW3#$b(jO&-bYPOH@qxW& zjO(9YkvkfyC2GfegZd^)yP!2QEx01A^`3b%bK$v_4Vfo%4$Gi_o0;^+e$&OySB5xI z_u~R6Qfq4rm-gTR`>xj;e3x;81>JAq1+cbr38hu7-v6vBcoVBB@E6C#wm?AvjUk!t zD}euTEZ?`9vIP@bI!#6*GqJ}Irv&1z*VHc){NrBa zPC;x#;134=k!xDh#5*T8rG-CSWdKZ_E^QV6S!n|;FZ>LC9^qA-!U&Rj^HsFYFN6r}?p{LE(~b%b-OX!zLUGOvXwR>*&> zz28<=$7OaFMVeIf5x<%&L@2wMm`qob-mC_%kBBy?{!iFTNvGJM$h?I64Fol?lWj41c!qFAgO!&r}%wk~f!X3^3>h7j*!9IA4e*KDBqosExW{w%=Mlyjg#dcJjg4IoGyt`cb&y4x$Uu6qRWoq5SAXi zrkRP}zCUo3XvuGIWA7WD&8?)j*zoLg3wX8)6TaB-<$z_wufZlFMNc71(|t(V9{ zY=&?kzaD28_9NKpi+Avy%$)_jjdsmtbOqy#c72fx0!~B9`*w{0*U*}NiR5`d=9YY= zf(Bp_zf5__F&$?H_8G%v@CI0eLd8&jc=M!4$BAfwpJIldg1@6V=ZiX0RBrTmf98Wl zPRZ#0_2a$DqnoEhP*gXlZ);@h=7Z}R-(s1#B3}G1R}B)5GuoP=XTv|R#0nuRy2zg& zCtfuwk57j5oRX$%#jj)@YwA?nNS1G~G}I48C%oNEQ_7n*sA6u>9I`6 zX8`|u%&WiBc942HzZd2epr{tPhJf4c)&gg+LTg|{+2-C93nUgk!A`2c^+lPn)CEFX6xoLOg|u#$HUXfWyZ=C0rwuzxcT zpt_pjO+-Rxory=?bp?}+{b(qc){f6c+Vbm+y4|={>kK%2JYO;Hk5-971+PZCwi#qE z#1q1*geQ#wo&e^bCcNDSRZ_z8ssKmem_-NR$R|-`qCe-sqIgM_S?{Y2jyxOShygft zF~AOx1W#qWMRfLlGXGg$OXXptsGb{Uh~3CR5PQ_Ab4x ze?8T)BpzRjg?&_O@f*(Weg23NYJHM2iKI@*%!t5g|e+HIWNbd)o%v3XV` zb8nD|RFPSJ5GFjR|IXQpcvd{3mQl*X*>ZwsGlYxatmn^e{D2X#4C0W4?-_(Oy$opW zHI2WVy4eLW$SHlpL^}Y%^glM zI}L|7@)3}hh**Pk6OZk7Of^wrwSFk-F#rY-)-m0lipMrayI$f3`8a01#O9Sum$89O zWVv5Xp%0?QyaupbQn)pk3hDR*Q^cx#dvJj{53|y2B69G+fHXcxkXs!^LD1@UzpUUUzR6uHl? zFXKXfp5DTcjeZ}iFKItM57$?d>AkkC{|sT6+YEkV9~jd8!ThKDUTECf_gv%FTqck7 zM*cd>#xW>Cg4i&X3?wUjv_eF283cksfCq2mR54fp59%#Ze-S?H1ld4q$Ou0nEr3hNcN+qk%5+(&642=YcH0Z(=7OYGoNiEoQQ-chM@I*# zUf3;rO_6YHG7PgQz``@pcVp|LT}w3dG-}p*26`m}{jnYBi30-#|Cs6}n(F!JoIP@2 zdS#at4)aNBG0ndn9x5C%$puI~LL)puGjBi!%miH*F6|3&sVc;!^}L8NgGYaa;hCCM z4Ps*8zhY0l?ho3B^{i3w>SKO~iNP}mmgM5vf`d)$G1v>{h)A1t%O@a%+ z0}2I88tiBlqY_Je5Jk zc}`}6zG$|LYldZ)!lfx+9+P7O94yT;v+H z=*FG{lGP!*IE+h0?K9)CN7^q*rU|N!sA?CfBCD8}JM6r~l3q`qek^|=s|`fF$MsK% zLmeREI}i_uxF(z-2cDAILcs0(oBP)%P}97M+YR18(4}E8qUtBE*X>8Sy+T9isHMYx zsK=%t;w`0hCRq)^1_bT*Q#bMAngWou&r4PyAAuWj62ayJ%N*S{E zdi&69e2+IV@*h=#z|hXutGw|M>Uz%qK~PHZYz0c4;$K`=7_DV$AeMU3pT%$<7M1EEs@pl_m^|f+_u0yz^&7+!Ep#Uam?Fdp>de$Kgt( zX|!NKoRZu+L(0PJYaLY+Dspyzj9t3AH4RJu3w}1kFW?*|Z2kngK{%B~1dPRmRVCJb zh>>P*a_wG3*>#9;Hg+>x)?{NM>qfe$&nAPRG+}t3de|Fj5U5@M_zBt67m5r)!!WbdO| zLVdTZ)XGOPJa3N^IEcdBfM)U4Yn|N-%VX;^=f?IgJc6hcN@1UysUG`Yw7#DzX5$5{ z76&ln`{`LY3e-5Ehkwo`z~;Spw0`y$KfA4aYjnBdL^YYr=%CJoSMH1OK-fo> zkBWgSi)Qqb*aGlsu+^`4QrgkHYKqlXR4Y#f(~26ySaQ*fe2U))hgh&Q;L`HR6&5YVD06X=!qMy?R5=Dx>J)xFt`J$>5?_`mAY8#X{E zh~7_n?+3A^_-8Lb6*(U)V^EZ4faOf6GLIT|lM-7c0L(hB#UMT@#9Pt{xQr3>XPa>e zJXI(IdTXxbGM^`V)bN&+33@P zVEA|fY*;bEDGdWsJs z_Ii66NdimDsB?H2kDaCJQ0+lUQMP`n>4=2p_X>lXX7 zl%L|wZnpip2))9eOc9m#fX&Snn|sZ$xtY}#ZKRmCyYg@f+sc!&A(`Yl*`0(98h2{g zld0o3*kK7Tf+NG{@qvSSh*97YB)g9fIvzfkQs;MiT_FYfjV}KS|HfnFMP6dK-FrsQ zf-QyIPHd`0a;uor0KYrQG2s!G-~CSOO8G(f-AMS|XA1Zo6EVQ=wjP4t>5FK1Tam^> zes><2UC8f7Lo1);cfI0wy$9iUmAq~UJKPGT)t@yNh_xM>*^L#mTLk1f#O%%-#OzW5 zv-`4;;6OH)0)y)}I+o4NZ__+~3P_vJiw}X2)}%dfC17**GNj*pR$E6^!jDj9;8~+? z^b_$$nT_6v*|$vhGdl*2#|ShjbLoDfPT-lgF?N*@&um)s4X2;@_79>fmRWw;WY$p2 zFwKIfaNPoiDJ~c`qF&FHmN8oj#*D(a+CmSDX;EEJkw4l;D=A=~#<@B$lblmYXs+I!E3Rj_XC>V8xkB#wQl5LxmU3p0d=U3MKH#2n2e_v-;aK_1 z=3|EYDX8k1n5SWr^~Nr3m_a~c9ibrhn&Qs}31WsJ+Tbw53+qEh823lS{Rs%GMu1`I zZ`>LRTkqs0u4k;+B@v4kjj+Yqc2Lguq2+upz@MtThg*j|ofx(sJ_LV=-ndTEBN#Nl z#m&z9p-m4U;HUd7K3P60!DBYDg z){nPIIQu#34FFhS8z!F~`)Z=bP-)F{~} z+IH!M)Y z4R)Kch-toNP*mEPIU9i1K*1y^YX%WA{EXzM@2*4%;ttds@k{*{c^pn4{779AR+b}4 zV-)EOYWkVZ#PG^^n_XfMo+n768vSr4Fu*>mkn)IfG$wjYC2_CmNFvIQB(W4PSV`_Q zAfqQola*dFz9iD=G!x3X=(iAPr0*WnZMsAR_yVK<(mM`wmw+i2JO%S*cWRc=ZM2=Q zFAbWnx0$O3CQ9>V=c-&hi)o5fTkznF)kGD{QrUBp*025 zW56*(rbEmyJ8Ve`re;UM)L3_~Cc_>vHKWbhp{6EoW+uL%?;cGItI>zyyr5C`SXkRR zp%^&PJlFNNpD0V_T4k3&IX5xG)d9l9C^L8dqMPO`VOFL$R2!L<`22I77 z|JqdC4K=VnFdqcAg7Ngn=&|9p$1&UQDuQzFS#Rgw6{V>mkOfSE~q2-wQQ!6|eU>F+oUSMMr z^Liq^4L1iP{V@up6O(JWa3d7#hMFG5M{N`YDVsh*Wz$E%Fe#5pCIR^`+u3QaEc1M} zV@Tr%g_hXZGcv@EGV^O(xl_}T>j|;Cg7RE%8?Q=selgKoNAU#K$^Nx?|E`JqU)dKg z9!c2Fo7vW4B1&~v@jPq$H!=BFbZ_!6+UK3PXlLUGy~f5$C9f03Pf@lYT8Z_PdLQrC zuQnyX%T^KdyMnkmQhBa&`b*d#;*Wt79o`dr-kPT^eqj%P2bKAb*7Oc!34>QD!#f~<-bMeQ+p*#!euGxJhdUZY%<2hg>HEome$d>c++Nxg4G0=*?0>kK zMT%V-GNw)hnMN;J9;-4d^`ED{{EYx&eO*~rXo}pwE zci6H5c6QUd}tq! zC)9(WV{vt9Hm-T{q{g<4Csi=(b{x}pWnm*$KtG_7mT(C9#uDjP(-?~B&DkbW4l9zy z4`e_R<6lB+=R1(%56-i6@qO&qJ59x&-_WJ#iSvx(cu%Oku=81>rR=XkNvytvu*)^c2X&RF6* z&orR;-FDz%V1OV9vk4BjpC>Su8t7Rj(L1q1Y_oS_x&4`Ge54vQLZqOxb6dH8Nn(I)fTrFK~(d-Z`KO)v?RGf!zb?Z|EdPV(H zn=g%Yd{K;>nnzE8z*qT{ozeakw~+>-eRRXeskqkM9*ty(T2RB8yJYNZ!HGv{*0=SC%y97i;-UYIA zQ020MeC;7J_?|!mk=`NpeVb16irP+p+`qxAxXn!TlNidYe{}P?k&b4-(S{RS(_h~II8UNS%bt+l z=GR}7O1}a=85sj!&3;&8irbGNw5@sO>5&XO9wR9fhG!V>j2etJjhw%|`-5JyA^H5{ zRb!Ryu-i9)x;PWiDOoU&A<6jP&7Hn`h0{iVCy|s;S0byn*dntY{%F7A2y|TwXP{r& zcb8?}!T4?dw{v!@_i#|IN1^WjIgC%D9PjQ8q@qwVNGp zz49KETQ_BW9mzXx?Ka1I#@YRhbxA!F+ui}|jJ?e^&FS~pS7(iz{dT_$QI~wN^TVO- zHRiK_39ApX1s5g>15OEg12P`f0LEfwCDk4jyQXiG>E|X5&5tbWWOKnII`@34{nHXT zNN}aMf9bn5;ZtoP-P_+wDTd4Ya>j(?+*iR^As6aOdC!KWopb#nOHixSxo`Nv?msLP zKZktJLX}fd6)A5+7?0VxXLviPiGHgDPwLKf#)h_6^cKs`3!X&oRm<4A=08<1Ea)Ro z2^NV<+IJ*njPET{jI||%$HlKSU8eU*?{(TEY5Ya2H}+ct4v7EHk<2rF{}%Auzu(`A z1N&R7{#uqte+8+(-`_~Szj6W|*k6tLzu4b=go>i8mapMO=DVBlyZRpo9!TlzFTAch zsqFYj!h06gnVp9tso469EBw=9F~VLG(W#HvYY%__%|z^(_Tm1K>;*%Dq&G5=y*QGH zk)FQm;u-$XWasNx5sMb>PC{bI*sk`;D%g|o-VNZF$WGel`bVT<=*649KXRpiw08_O zJQCUDKCWH7D;ayo^^Qn+k6ip@LSfr`65jsr-vZha(?oLX!bsoijNBHd5j{KS(6)1S zqV~fe4&-A6=KPVk_&0}~>3T12$q@_mDas>c=luwOkK$?I|4xiRLXYUd3Hy@Sg-EUY z6VWM;#fsUSjR+bqmyE_aOGHyoBx1St!|3F!B5!2M>r1eeb*%5=QU3g**va0mMW0S| zu4nXp7e`_xWd6i*msHSv^T_B5U!d;HaWi-6+dR>J9OhD!tMI%ovrU-mk8r)iUDeC@ zsP8{0*OSQ3inPKCYu`@Rq6qIxuIo3t2 zpW(Cs`{V2$cX$wi@;oG#^mg_=O%D>;e`O*bpTC%Y65eBGuhV4ql6|JGmYtppR{mdn z`M>z`{~TZLF5oXu1?*-Jf59Fb@R!nq@E5KH{G}{Grl4P(Qk5`qn9@NUrZnU*r6Gr* zT{w*Fb=gUKQhEMzG+vbOPBU!g zT``pkvQJ_qhRFbcJd=6jl4H1`;a;$^nL1;Z)x5zYZ+w!~yn(;}@RUC)O=uC06qk*-0U**>gbf z9{nH8ZypLt+m{SNw|G{B~Vy-gug|3S8>_{tm5Ghr*?_ zKZ^L<&eu!X7$CNJ(fhH@^M}dJ7fVDIz0UGwkSorbBjg&4SM0!ZXtes{09xHJuyBD^ z{`VuX??s}^<n*t%%xEO+=%?W>0 zLKu2F7@GT^20*zylI9GO{^5{F+B+CYpXBrq>){QbK+?yf-9Ip&Gi#y>JeT7F%B z76YVW!E)6r&5hy`KJ0yN%;C~QTpExS81?4ND82X#uE+f;Je4F3eKltZZ*OiTzqAHh z;MKHV^>VrM`DOjxV>UJj*WVz%I1px(5LV# z(J%-8kc4>Y7DC69=R+TtUQS znDV54TY}#vPK}kMhKs4-VuNH^m1@vaSbhV|*k4thpfzKvxt2YFC<;?xyC-}J7bZpx z$^clEghA+e@&df|lB?e7peXUG>SZZ3=l!eA8Ch%2kAf5*J$@C{1ECJ?fx_es*Ip7h6T-0*#*|QTnZaWdfRD-y#3%4 zYpP}M@rI(chE4vAhE0kY)i*6 zP>=itU8W->F%w_iA6bg)h#X16y>SBlS}EnmW5Jypl|hWFV9TOknxtYbJrvur@V&m( zVJC7I0H{19h*q{+P7twd4{~1)?-QnBi&+F=$o3?+&7iOKVQS=N+YZ-njZh1NI&~Dh zlxJ+L-%$oOw)nHknb)SA2}(S}d^dNYv09jwO2ZR>Q;}=xiN(FgL*?DXoh*5CG_Wx- zdo+gG4|kglKtaZxFWBk+AlO}^5Ipl8v)2VC4{W-G(QWkB6JB=$Z>OrOw^#@y?qim$ z>GJc~bO^6=t4+A$7};+)uis_Di0b7!+?g1*)&$L=d$$NzEfCKl`iG@DLCy}*C9|QV znvTz!iINM7BK{*Lr7NTH;$1vIUh$2Ymr==CpT7*wC9-D`XN>(MJD=smf;8^2LkGRK zg=i{I*zyti7U@3oF=pfo>alr%Sejkl3(Ol)(WFYg$x(GR@iX(PM=Ogxe4)Y&h^^GB zZ+E@7c<|ZU=ZWoRPBGniZ}Y-79=AI~(X*08)AeurFs8O9cb&KrM*zKCHX9-_aQ-n9 z_XGB#cyUcx@W6EYYQQL2{t zMwP6f7$0Rv!$OvKIDqf@)$G)y^L#f zWd)oq%Bs=l5^N1UTUNj^#)%tvA1Sjz1KHTG`n%6>PxQ>VKm_qf=kl^Z@2~ef4&8JSm}3 zsrhL3$21OInY;#8X)Vr0=s$4k6q5t6*lD-yE?w0OCC2-eDl$1tm6}Gdi(RQtLTC%S zcdPm=TT8gHhoRVP*~fZANH=#|!$yKdky1<~#7IM4O3e_*w4c-x~j zkHn+5Z(zmVcN16SrKsS-^W(A=$5BxN`Bjl7nETS3IUSl<9j$q$|Kazd=T~;>Rt@dJ z>MO4%j%{S+m6?saXG8ynsoAkta;Y_aD*I=#kIxx|`%q2h z(I4Cu5K79wxq30}XsmDmTU5${wkx0;(TI0(h22@t@P&XSSYl#9<*Nk?s=bW-v6L5) z7RcWbq@d>;nEyYwe>T zWe04Q(oMvu*$)u~h2geX7pL(d$}?3I>w}r?a(b0IwY%KnE`w;fA0mweqqN(IvC95X zvl)mz<~Wz3u96j2B(JbnCQ>-oIMTmOhOkZeGtD@#4887MNW9gB72ef4aoAo*zu+KTV7CMbRm7o}IUx9IZ23RNvfT;?$%H za!|p;y6Y*GW5?o|Wg#e|6I{XzZ%n4nOlQ`5C+h}XDA@HuH9Z{o80bWygwXb77lFJDRv#Ox0X>%dOV zwtumR6G95A448Vym+=Tt9bZF6=o=mEQN${n-b(hvSI2o3pHN3|8Ih;MoXFuXgd zH?m2v%Dmm0-VCa4q1JZ|W1Cvjw^M7Vzo^voDG+?DEhCV}kh&BricnJCc{;IX+DoDR zq(u4>;zwUCNvz#zYlit4`2xYXcYLWnW-<@O+En0n^m>0n86L&YncV}jmmqZhYn2JH zr{8BXfd;aDzxStu#c(Lz?0?l_NG zpG$m~>wP`4aLmf=SMb7abJq3|?=kksE!v`lLLJ+2i+8Y9AHWYcv7Sd{Y9EcwjK zzcx@N;kLMcq|>X~4*evu^>6I%A?YwQNO1yjP z!jqirr2Z{??UKGbc0$MT34h3xY~+dVO-b*aq(^4pj0icr*E`-L3qQrBzQ+;op73gu z>9<_(Te@|d5R(wTS?l@i_-yKkVi>izzT;^^>X?Y9U4N((dwt=T1#XAfh{N631Zv4l zeU$rP*b^zg>}gpn(-YKMm#X)Bk7QHBis`CpDRXz9pLL2|oS~hui%O%*Wj12JFAB{) z;jNwIS5O`3$Ygqar0;hkY=RQ{Cj;oFucrL*g8MrOe^P0J6tsUy_}@lefxy0nz&)v4 z*RV-V!i176O?Hmmg#qD927IGqz0q#74avVoy8Gv|)x`J;mCp*YQWg-?k9^vV~fn#7{1C-0WAFoOPO< ziJBY)tt}=PCbFf~k8DYK@Z|;i)_?l(i1)arM{~0-b5GyphQ7=MZH{K=1D)8{nIu)+ zWRt7(QzSTTp|v0kT)pz1Jr54RM%W;ZGt01&m9a-0Z*%+C07&~e5GRu6A^`Gdl0Y z5N3Ph%Jqx~=+;22V8%IBh=c5wbvBr>wcSnm6VM#Tffi?j7F&fDXM+}BC8TpLFOcdw zgq1Cz*&Yh18JcY?H6(jd$G=0daLKb(xM8wa@l4-6&RO>YfPTe3`R7DP1MOM^r(<}~ zn>Q8d`%zBOU>N9k$He^$Bgyphz3vS*`wb?=xZ)m_YBw#+w5DIga)lJ}vg41A`?Djq z7z0~|bxdNM41b&75c~7OS@G;NCh?Ju;jy;Tcyubs{+lT)2;-voav9ksggy#HsUH>T z1K!$+S+|H6HbQTiyLpo0r+kG7gwb(twjNX+)Yk(Ha%kL*ZS8nEHluXmR)x!Zn-giJ zuf5lI6ZYV9P|v0kYWXe|K%uykEksMm#RQ-|80ULi4EX$^eZL}iW4M1##qMXlb4K^= zY$aeQ*RNm~P9eihMeXl|sh{BjgM4N(J{2_(ltIG+P$~`ESOM7c5n3 zTX+Vk+5Glh6Te9aMPbs+A2odS?%c*u?B&lrXIx9H9($6CtYc5AAE+PAo>4&<*|sg$Z)3ydrk zJUiO7pj_4%b|>PP5`On$UPHxq`2n{XUNn0vhj851G(kN?Od7qPWwcw5kkRY<6(y>M}Owp~t*>%17 zZ3tG>OLQ@Pk_L8Qa1y2|tlmcuTzN!f{@T8uF#xu$nvR)2a(_;)8qH5&UmKX03S{U&zc?1VK`f) zcMZ&8ezwe2JBRWp@CXQErYerXnA7r(lUEw!n8ZNorbbWhUrUMLqSo{=GCJ@i#b1x{ z%1T)5Kj(NSWga(K%$wrWRL?$Q21ZwtX$;YF00k+@nq9x5!K*lx#rqWhFeH6kS3S`# zRY}sP8al_GL`Yf(4RGCC*Kv}qYnqLmno55No;=7MI+6M3q6y6v|JhzRpV+vm)vHbUKi5oBjT`dK+B&si99#IC z=CX`i2c*2rN_j5WP9bI0*uqkea&tWcX zZ5|C5#a`fOu8#O^4}RP9+rcipPf)OE8LAw{yVO5p79@4V|4O88B&rK({w5`8T)$h^ z=92#E))h}Ij*Orr=L?w)3bkxA>j%x6=3MXT5^5%>JYG8^ThQNY;D%)(!gaPqVQ!sAoF9AiqYr>WLw) zMOKNkxG`#0M!V$kw3#uPmq?3Bc0L?&i0xeXu%@Gw@3d2ryLyh`BI35ojoD^uPRBp3 zG$}i5`D-c&_xDaoS1z5JuK(${UJCsSSDQ1{bExXJRY|+kw5hLuMfXYl11c6u=zf z%=>!VC(BtfKMb%TmF{C}r`y<8r+B4TP0o{ceMH{-UnQ$Stzg7ubJVycQR-^zrGm_S}I=>HXBivG8WY0=*! zrgJU-&C}D~a8ddj^wc2itoc8qr~X6I6CRI)(bI?n>8bZ`(v#(Md3rL-E=D9d4Qu*) zr>3iKoSdHdbC}!>2hbCQ6cCj~fONa96x5&%nW_z|p{Nv#z)R*nab^Xpg{UMf9hCGJ z&KC2)h4fP3rIjD0#qlq)60TDE*3dBN`zJ1+QEX}#-rgG-S zY*Xe|G<#18y;)YRU30Y^%Ee?V7<*U3h*276;`3{a8yxJJ&QqX$BD=}}j-bt!)Ua2z zj@d_|-9vf*J_DUD^AZ%L2!1kSqFv7p<6tib2@ZrQ+v#!&s4nK0GXJUcj)Jcqj|1BD zBwP|*zy9`kUH#5+e&sL6*Ufx2k{C9VxQgQu^zh17rH0KTBM>&p8Fg65>7BOdxahJc zN*NzJnn+qA2egDk_Kw0iIlX#b3JyI_5VjpzWx(3%y(h_x{d@2zr~W^kU?e`?H{cF`wN+1o6y(3XKO4y9r? zI|Gl))}M;qx3=>Yl2~`Td~B}4nsC1_T;tvbRDB~~ks3jEl6IuMpIqMrdr8g>du+CK zPk0I<>M}4)p`VFW_5e?xoo?xXMnPiU4m<&$W1pi^r>>!Px8wcKQvc+Me$z43DZesa z*WlKE;Jruw(*FMFl=l!2Gtp%y@ilYQbsR@DD)g&E;%=T^Jtw;2Y0`Pv5=#A6cMLQ3 zUQ4B~4=!2dk77T>NYBwS*kypMRjsr&JLk)2u90dg`u|jeR)5*ZP}_FG&JV@QrVUC~4d62EU_yDat) z`zD5wZxZ17L(?o-fSSXE9|2&N!jvZEbgmuJxnT%tTWBfWMZ2FzVPVq90+;+=W0Le} z7L&&HrocJnX~W)uomaE-3W|0xZJ5i;(6db%_^F=)m?%fluJ1!`k_;(P_Ip7m-aLm? z$=mw_nq)L0X*YJW89y|#gHs7j34K!>!OL{A)libubKox^0i$*{+McOv zS~fJojr}OX@6~(WaUs#; z<)XjvzUtq!YNt1E9=o>nZ(uKD%un{s-gty3ih}r?xc~Whb2`#-Udnqs5HZ9KH}eGh zsR)-eP!(s!KW8Qai^$<-4z@tYdRDZaNbdp5h80hLkc?nEdgddT3!#(%J(=>(u3zOg z&jxM81q29)&jK&u5v-dn`(H*Ed7%0x^Vz>@jQRk^GR8ZAw>?}7$t4}RN8DW`6Mme^ z5;3n5ea4cHKV(s*5+ni1FpYW=c_CTykYG~QXAOtZJi$zHp5*<#L4)aTVM z9ua_9e=XZK8(w@|^ZBHaCj7E$1!@Q%1TiuZ)e%8#a@xJCsB`RPlq~Q#4f~}H;AVoK zj~VEE1H3a??-uWr5ZWHDCeam_6RN>7({4y|4~=j;L%@-le+RZWgFV0y9=g`=?k7^4 z@GO_`>+D^eky_ivgS&VMwvBu-VGrTk*KtSvTg+t!%T_U#hxlM&UB9f{V_+015O9c&h?C_Rl-DB)KOtz&O9wyu%;9uwFrLlfBt>Luc8L@;4Ep6k`+ zTwWBY7IQHLlMa{gun(>H2XSAor1D7=47x*mhcTGdJnqzPt~<){j)WSABMY<-hZ|N$ zyQgaI*~$fS8C?=3(qU5efy(@ca}C@UO6!B-fu#czWS4>zU&Nfb*qDT>|9I_o zx8!Jm&&N&)KQ=bn-A$Abn_f)@Gn(BF(hA?jh*429%;-$59qqYo+{v?^a6Ew)p(Jyd z3Qi0rsF;22xA;enudDb;iYihbA7+O*LQ$w@X67O{lBOgOF*!xKu~3MStQK=7ys^l8 zv*{{3t~Oo9`d&@%W-l70mw1Y>9^j~h+}XSh0p!KAU+uNfwv7Z_j!?PCl6c9uh>?7v zE0*$5_B!;g$OEP+1eG~F)Aw`Er*X5mJ(}{rMnKf~h_^QP>ia+<{Z;B7zf_Vc z`D#t8_UtR_dxeKJ?ZxfoLaG)Hv4`gt@N^=5TXhZRpe5lKw^fhfI7QNd;}6Zv;JypD z7HA%-=SIBvFV2#E+C#>PrvAzV%*p-suY&#cMsjDvVlnr71%^BU1SC!DUOI9$GErAD zy&rY`At?AGmrCUzdfiz#s0wridku>DK$kU2ODKWVpIMO`##e*&>0tUVO6%DTDS!E5 z^(0V(tK~!rn^%zo^(2TYRqU)-hIZjKdM3Jv_*tOzpbO7M0iK;# zrxX5?TlD1s1_XIa^EF_hr5gx&%7Lj_Su z$^$#-7Peqp{r_Aa29MhqlNsDnej$ck{QUnx#WfHegtLP%Rcpc?jT~mA--GJ6$RBO! zxS=4%Y^zlka-;5sO7vh=H`M<>m?%xR6-_s!&xzT}o1G;et%O(<20uvET^6Xib~nNT zRhKy3PpG&w0D1f508Wc|kJfJUp5OgEMHZq{``p+X%Y5fm&yHq4gWRa~qKC(e36HtW z=(w&wpA?u~YhVAIQ~a>AWxree4uwe$W%)oMo)#*^NmJ#96{$b<`Bg@@6|_b96M3Ryjquno|>>9HJ=%p)=d!FUqEsYqZtLw`~BfhPAF`Z3Ndn`>E(54$F zvduy=p9YgUo*>$L)q#+gvkE<5G@;IYGLjmmaBfuL8A*!Sr-osQ)Dp+p$Ed;_NELpx z6dcD@f#A`G8j7!^O{(jD_++RG+ohw`Ba{*6go2$XrB~If+m!gaW@1TYy%T$M;Xlwc z`maL)1_3f#S=0IQ{@UlYQeU7a)YQPxV3lA3MFJ&w9m;4bjdaawc~}ZWLM8}AM5()>bgrlsi%rJx zFM~5}y@8qn-bf2RWk3tAFJ+Zn8m~Lit=)N`797iK!C#OT{D8r)I;7lYyeQEXFAZqH zVy5D`#6wB{(qJSP8Kx>NI6RhCDzwzINVTU+48*~CI9*#A_TKSF5SF+!nLaM=*NFxs zQb=Z$5V27&(wd+I+-~4AcANRu^v)n^koD;dr?`Un^RgHYef;E@MkaXGw`%p<&U>iD zV+T~?pQ$CfF&CknIWzGTmTrt(;&eVdq;nlg@t-Nla08p}VpBjVmZOJuu~Fkp#F|oh zFn!EwK;SZ4=_0>|y77|*y74J_-MF(vFvAY65viMjj_fwiX^v!mc_=TgiK3lLB`r{Y{|UPHTEY zs2#Ott50u5(?ZUyrd+aHoGgVq&ZB;qH0FN7$gINR{TXC;vz5n%nsYe+4rGJVWSBq7 zt$og^8x@*QfaqMoK**!%7czOHaKu&9NmPrbF%!J{>!ijl=A5aJ){Mq%pPZbXw*h^* zP;GYoe{`EKh;&e=<#FNAW?nP;vR&N=>&paW8-@9gP`y=@qf(T^(S)OCa+sJgk<71! zjknO^O!GbMzqb3$Q>BliPF464bqYt4!dTQXAt-IdFA<2V&0+h zJV(m2HSbVOg7IRy zLp;tIKg?qRJuOpeH{GC#XEd#okjV>&vmZqfnMZ_9a9S1f@Lh;5QHeG~1dL zA@NQ821+u;gs+m4j96>otF$pt^M)d;9}Db@^?0vTw7N>dP$G?i%^XpC%R!Xo(N6P> zNXG@1E5RjULPlAp9tE|_U^(?-IU-i!GewZXnK9c#e?ncph)83KoJA)TW7-R4-~RRE znrHqxlDThEHu5W4VHR&QtkoD-jlTRXqc7umhpirl%wK1SVII*VpVX8o&Emcrc6c~bKsbu*gXVw7QP#SN6<*(Uul_XqB1&TNa4GFZtIMB~g& zWtSOA0VVipI$c+BCy~Y4LlJ=jL-r2sR$gj{e^{X!+yb_1SQm!tCysr;?235FaCYDx ztofGH^P=3>c>yfWi(zjV&DZYSnph3NTv2jqB=&f8#g+rKUBSO7SEcXewOy&reZR?T zyX7fT|4eYE_i%352O_7hq3*tny8E@7B>UG6>3cP=?T!>NN!xYE(J!y)+H$SpHK(AYK@^z0x?Y~lTbE3t)7*j7Wm%C;)C`KJ6AKY4F8_Xb>{ zg{|pLaoIz)dP{f@U0?ynMu}a?FDN1qqr@&4@Y4$R;RsBNnt{TLg_?O`HxAypgLUe^ zb?xAO+MCpUJDWyfvONv3Hh(gWv6vGra29ne3gwkpfdQ~&V3AbzxM+s!|4W;+*e&%F^Q3V9o$xXXQPFjlgTVuFfv~#1` zwMc!9Z^gE>L~qy-+XAV#N4tJgs+MOGScWo0JlLv$wAaVIKPR!YAVN-)jwP?-#BB9( zu+EWA=U?{6YhM-{ZZjk1b0}H1GHSS-<9tlyU5`(iI?d6p4^e*PdTbN9?x5=k6y$|X zx68p&F4&|m?r!7+SxbyfhgzGaDen}i=ndQ!pYwlUwJ+}nr96gKIU4P2alGz0xAxDJ z`V|oNtBT^g%@3Ffi!Pfj9V|HMN^;^tyMnG;Hyt4ff8@OAiv3m-Gr=NgU;wE_J}4VJ zVjU-Pw@G~L;Z=3d{@U@hW~YA{`S2K4O(aJ=&j^(Cyd4c{bt*lJex3w_(nlr7Xkcn# zvpK)M`X+uSO4Jb=tmcGGHHCa+al=PrI3>;~uJ{dJgE3xx^F*)uw{hH&aomy8vJ=tl zb-W@4Oit={Eyn1vp+wBmH=ux#^m(iFFL{#L)lMY>YE&YifrE;?{$;fe?YBvv)yFtB z%m@1>6AHo%oRib70)}{bWr@ajpmXxqNO%U^;IfvG*de`m%Jf(lfSG``B1nvK4j~x ztVH?Bdn=&_=;LpAEAOSPgLx~3DKZl27l^iLo_jbByp>CJ7${&w#{b5+D&?~*a98Tp z!FpHduACm|UE6sg@KbI!hX?Uf{@JjTU@`l9e#$#&WpbgPGRoTm0hDUtCLKLgyO7ST zynKuKxbar*;1E8-cr8AMbH{uc;t9N!0$T`s)Tz*0sYgEHt?c2VP*1;q&s(W>59+NP zJ4p2s-~xB009W9yl;#z7?33=wsK_v2rqFXn?n+@>bVZldxH3q$H=AXI@tXyLc{ig% zl@C3Z_ZeZwpMOYN2`P7`{V^&a52ymGML z66fEL_V!eId)QgrOQjQvl`f}>#RvK=Z(>-e2i9--4Woyx3Ah4$aj@f(RpwBR%bGwP z6VRnlp~QrN6_&|JB|C`cQlCGVdWPq+RS0ls&*h2S76-9kG=+KWm%xcFf|QyjYyG#3 zUuB<392^<1-Rzc(jC&*fNM1|BZFym+rTq=JyQR0|Gx#*l?bt02?@jrbcS=^+p1r z3{L{e!HfK={FcX|!M#p{MY(O#xmMXYGqz3BUO@K(q<(rW8~VVGfuSuug*AINruEKs zEs0_57RYXJ-H+0edCPe~@1~BQqtf9!suII^mf(Zgn9^TG=MwMW#@;FuZuUo`h4F+y zw1XxF_F~m)V}N!%`@or&5gglj1cF`e)XjUWh-kCRi8k9{qRp&{9Yo`c7}XVGkBNOh zCUy>@D=y?ina}d=1t8f18*R2Aj5ce}rMRu;8E#ST3{LV&R!s0lwSZo^+1#_XOTc;s@I&2O{WtF2!o5I06Pz88F{1Wv;yP%yfS;ml z*(isQ$I{rl(d*aey<8eAN z7$wElQ|anESnz%scAX*sQ?eB~YQ5hIgFIo-M>4mFgoQFz#hi*(!(J<%4FyJG8>Cv= zNMOCu!yD+4JNVIGsKqdEfPFB@(+VG(%y?8v9+c5_==3sQawSr;?#_8%%~s zjIxs)<~5?m^7=D~;nz6Lb0ZzorUdrem7(f{Hxj>wUl24k!nie*Y?Dau3Onsrl;SE| z6ZR9YX7jvLu?I_ly@hX0%3|gBYxqVqo8w&0M}%w39H}^mO14_CxQTmwGT$suIsH@> ziL599p+zbDHwsYoM>)ku_~(|^9VZ06L+`Ud3MSsUWPaMzrytgrc5b?p6FY zk#6uwbh2&>&U=fs7Rvr>tIo%$>v03E1oehP1xgs4j@*gE;&L1ovUMLQHa}?wUrm%> zomvbLLrOL(+Ya7{uJ{DF!$r`!D}h4MIoQ?NWd_(ML9l<9>8AqpcYC!g!U=c>@isHe;cA} z!q_-YAe`~KWO_IW6y^)qwAj+@5%2+1Ke#8Y9TeA942S@lr4Xxe_tv17r+fxad zCHjdVU^vb52uZykHD?E}fO_J6vD?gxzen}Zrvz? z(5qovn?K320!?aW0ugbViTad#qsHuB#ptU-;IPdQtI4%SeHv?kgPZwusZZw?a4*z{ zG4bNa8nwnAB1G#R70Emh(ua(1RN)Nrbl~vQ4Bq<{m!nItC|y550YNoUJ6iQYqc=}W zVPYGh%FQX#{;M!&Iev5PhfdvT9=O^J?uH*IXzV+NBCYXBoJt@hEAY#}6Y7DCw#ADp z@6Y{{C=%YO+aZ}LN5K;4#EP zaSGr#2M}g*f8`cN&tdmT;C0DAK-x7?fzcGS!ejGtzd)}E){ahmsf7M@nIQh94Hoi^@~}1*6Gi!_`Ax1?8YRMp~}j9bAe%oO#5dJd6{IVmR)VO2l|DGPXqTemZy$Xf<`dTg(qc z$)-rA5rDdww!(?ALhVYf*t=^6-96Z~a1Y7gBM*s1Q1;9|I;+iyXl$r0JyErKGvGuf zkiuZ4nT}L~yc`w9y^D{+CGfZ#oB)|y)9pWEW-yBj>(nXi27c3TsZj`f*@&=pCBd^* z=2L1bvo@53Wx-#}^KOjwDf6|sKM_HM4@SpOX8)t;vJZGsdg$DKmIAF^8MO)TW3@px8LE2; z7Ag#;#BgxG$*FxWUi7c?F8I3-#TKgR-H zOwJ}2;ol;e2i4WN;GXGrfal}OW>hD~Z^DU_oj9WAbE!@PM zyR|RG>qZk zepF%cD3g#MQ3VwM6c&O~BB+McsUq^<;lv+b-nl2*PFXb`GP%-l?Si^c-2K$0_~H7i zpVSN&JZ36y6g>MkZc#rgUy9136_uizMHj+SRHqa)lYg>n2H-bydSE#!S$LWUZkAtn z3vIFtvAga_bKG}3jsG7NrTUsEX#gY#jx|^Rx9|6@|HK;~f+fLd4pKsDe&Jnl-mt)w zj&q0eHH(O$J&1ZzB;KK@%c(~^0HHsoyi_WE0hOiRH)*QuS2_nGt#-2Kmc)zSX)S)$ z@t#u&NOny<*1=-Hc5LIanZxbQrK~8Tuu}A-JCa_UN>g!gJ#$mpq-^_+vQ)OEERl7u zDr@!Pvy)y2m8R}mOxKcLw}3AiWbs#5U@leEXsIbcPVkNTQzbkX8nGyysft(_qWJ%E zwP2-(OOO;6vL;+GTS6~f)7GDg80`pVb@gH%eF$hUIc$5rA@H`Ixxhe{8Y1kK8js~j zKkK02#hy@q#i2@Ru!>WX=|_u6>Tx0*)Q;yWK@z(=nsnxnaV?9rJ?Y*u;P%XvaF#H zC3U`NC7ZO))d9b4!S4e5d&Oe?@;7)BR^h4sxO$U0Fo&91{c-gUd!$1tO#0*SUVEg& zo`FLRUVmKOY>#v(QBQyWo3w9%kE*)fojgF)G!rx;Dr(f|A0%RcCOgprMTkN`f3G6VjF{T54l!uh`m(R;#wQ27K_S5AapA*5ad;h+4o0zUtiX z+mAUb2d4es-t)`kob#Qv*Is+=wby=}z4yW8E}n5DKg*iDu>Kmm=j|rN{;>bdKC~GJ z@dg<@1eAQ=hvqCgDM9~lw?{BK$ZuP4oRgo^2q>B0n185(0G$Xl9Pi419_NZtn0fVJ z{zyU?3@ucTFo3Sk9r=0cye6NUU<4Ao{G*ob^N+gbP5-FHJN%=nH~L3?`+onZ3-0uf zD*v8;RNw}DRE6C5ISp1lYT}0T9EPkIehA{nWhO2QDLmxlM=({g)IZ@8u#0B~Hf9Y+ z6Eq5yhei`j?!un`^qi#;pVOm9VV67y8?k<}bSO5$VHw~HGrf@<`QuYah(ZbAe8{cs z`B0HLn^=NW_N>-Q>iZg`*e!4ASm|8MuI?gko%x`oX4J3A3m!=wJBau1Yj zi-i+!|L1J^G93F>7)tvtvt<|Kh_f52_qN9y?;(IV@TN1Sm0E+pie=`n_^hz$TxZjY zz9C^WJ93;%r1bc3=Uf1PQexOoQ&LiAEsSgd!mD7r|Zo%{! z6|fa^;`&rkK~10SKYK>zwbQuq5=Rt#kHWTm2!ASdj2%re0064YTT1+AXWnuxK5veV zH1RQ);?G;(A{Vr7_~eeDzii{4-2p4Wo<}GX_{jIpE(Z3F2ok8e+rIz z0<*i)ombT^oLo^f^wB-~((K;Qi(zc`UMS?S_#O>G;PL{Ce#KuS*+vmo@Uxm_! z;G;wD$1AWucANQLQS{ZsR=nQ$33kkmUGx=S__yyF`>C$pi{H2&-%fZX@icnUw_xY= z@@N)@-!oU^BhPxe}*AF5Zzi~pD;7b}|*z*p_@ z?Ii5yUWk`s6A^uX5ni1AoGUsC^}E85r*FvaP|i9b{YZ4s({-u zlL6PG<{+A$S>gB`_;|dzd6>-u_v6^k-!45=ekZ?wW{tQ4JNwQ;t%!cMepSlhg^8@W z3RPo0cD)%%s=&vH@C7mKb36*4bvOo*p)YXeMtt>XJHL9Qg@!%vhdqRa7{N&EGe^iP_uO zL^(DzmM%i``JuwkDNK^#`EU^e^xSm1`Ro;6q_qu?mn3=;Tb6#snGKc4*+ z?B*K8Ao#T6T-50^w+7Q#)xV3+THh8p@Y%nK?<6KowHLOa>dj(%A*-9M0@YUdhiY;B zNBJV2_K8SO3jQSn_$Qvnmnd6~hCk&P89uVdZdO|2`DGtypJCb~L)CX6LjFHyj%E73 zX#J;cZ~TY$3fd2I`r7bS^i6C#EbKvhVX$toe4)@k(+ z)s!_>H!PZzcjbcW=ITS>b=O{ZWwY<1x~uEzudB-|oxQA~W>Vhi3y$!W)-P#jtZ8a8 z;g?i5UVSju;DxTPS=QvmbkrVxwbfVD)cPtLm)2PcRiY#yL_RnX2GQcHkx2JRMpquZvE~i`Fl#Yi{xdYHRDG)y*|?>Km_~ z)leNpmeee$xw5gQ=8(^pRJTOy5%D2{UHk9CH7u!a_LVl)Af|z~LVfuv7T1;5Ut7~S zDGy{d;&x$e^_Akbw&q&oq)V++?B3TlH7B3W57tCsSM^Oukycja9Ani>mNhrP6q~e- z&T6P#Y&9$FK*BmZD=%Q?l-Dh8o|LCzMn2asfSwNV;0mSirlhqu)+}6HSF@z1t~swc zY4_8OJVqMS(Kv3ujmM+k8n2E$-_q!3$urywj(>dX*=KmXpQQV4?yt+<{7#3V8#7gh z`?fjnHF)Z?+k447)og5csNn(yNJ zy3$fu9-WBq-#n*V`8Us-R3U59f>=6agtmM{f^z5<5$kUjBi|NR*XA`;H#Xy{zD{HW zS(P=`Uzg-C1MHH8xzY7!(kQeTXPu|LK(a)Pn^V24(#BCyv!uRp*`z$pLP-n{(A3&H7%yk~+T$6M9;r7-9iXBnJ8vaSVI-|#kS`x}^920?Ll3GMUFj<`Rv7)0 zu0zmGbNL3chp)`&Lg~r_vC4lz_lT>1RUW!C&S!ZFTm88y&;qOc7vTfu8uG7BFUuZo z!n@_MlomQIyGjRF@fR4G32i!DKS<_ZQg>z9dy}@~=0EMaR)im;gZqeg2z-vgDepRg zzvjxT{g1X6$ctR3u`7AYvNst0vHZR+!ryB6LS7c#;qeTVUlv`I;4sUth&R{hmXP%U zN>AGFFlLXQ%Caj(crG=w$3`QA){|S#=(J!d#t)pI-Dl)xy4Q&C_Zvnc{-maZ*_F1C zcH69F_?JX@em|XuH-4kFcqa4~%y#`A?L5~i1J`P|039Ay5>P%*S@_D#u8erP@{>V9 zKhw3}a^2d`ApQO;HoZlxPe_;>5tt)7gNMOfzVV$L zj93|ESEdP?51NlfxQA6Jyg14(ykuo&JiRLeg%=0q8)51a-d~&|AHg4a=$5v)p=0=Y zB7Bj_6E`0srv9@WHW-h?*mV5sM0o4F-0-kpZ3)`dAFBQn;n)91{RXqEXiYkLoqpq^ z30-+`cvB9n{KghV_<17yEB`S(Y>+7t;n#`qKXJ>yun!wI>wR0}X$H*a*G2dVZv1qq z@T}Ue(*I-{U&fHf^B)f4BLq%+<3YSg;3p{*v^Yluo@ektcFqbGL58ap&-a<Ln<`-(wgd{?+M_0P+v?m#Uqp%Wvy{5svx#pa}OD6Cd=9`f^3aN>pZfz$n-2 zf{v>%ct9?Aaq1;(^rG6IA>AJHsd_sX8@k!!-|?R!=>A{$H;Zt8H4z<3{&j+G*8hY2 zFNttNOt?ew|4Pt(_P^v$dn?Ma+VS~bbn6$>4zc#4^y=1c!Y?+9@Uvxj)ef=YVXw3| z*b7>;nYLlB@?V6H8Bv1SQ>Vu>XLb!*F}PxNdUpopd|l8zJiz}Rx>V8Nw;Op15Prlr z+;pDk>c_PAU}q~)dyZT&s4Tls*;_==-|o_Pr%zYq!1Na48Kt7VLBG%;!Zn*HN8r3p z;6E}ryw>?E(^q6L++*VT1Lis9eo5fJapgd}N!Q;i2ARqmw4~3>Hi2q1Dc*LmM zwJQcqLpm96k)Y?BZXV3R0+bZb)=F)rG(^|jO$Gw8SO>t+vop=5U zw33dP#@VTx0!YnRFXuCYkn@;pR+8xi3@F|3py)a}M(yUq3E z1KW*VB78{J1D^0@Xf3)tbVMrsBK$NrJmh!Vow^o~9Nh3(c#&+6&y6l2zf3>MGfHEI z8@ue^MMU`5|BLWlB7Dhz5&jtw{wm}950+obj(W`KiTcYLYEzF1IXU-*1eb5h)&o0ym4;st&Y4G<8=O{~OXy9tqv0u&ev9pX+diZpm?FZhH{poS7Pt{d zwU25AeuAM7X6sC&{<_5Tr_A%R>|H7+$oF3H{Alx>_>+gg$?tW6+w{U;MCd=M-><~; zxrQH}U&vm!?4Re`$UyU!&b?pQ-de1X7e2Rw+k3j9)qYJ82rhYS2( zfirzPRQd&evW6A@y1+*Z{9}QSHFy!uS!8AoH9-T{$_`*js=qAzQ-+Q~f+CzXManl% z;5QihuxSq$;l5Qo-)Np&yEFasa`w+d9=m%`gtPfd=ox{JGyDj>BXE1k^H=r;*OE`J zdP%Ptg!M`3vq0dsYeg3L9BJ|>67+f*jRs^t0iRV&9;cWq>nEn*evNo;+lSCgiuRQr z^|T!~%JY&4Z<<|7{`Ung^^-X)DUNFY@{W8)2%K{9AYLSJYf8-Th`=u(F%Fcc8MeJr zE1t{p(IIfF55}`j;IiC2C~#}Pq<==>V;DIO;_nDt^7%^Ol0Mf8hpUH z%j-OWOFqp4AFsG;{#^n;OW=12{F?%QOyHKkuZ-_xMwZREXjI<#G2_OJ&l^`*IKJ?l z!f|;cFT@*zaCLKDWO3cn7X9?BqH&{qzA;V9mNZvifpc@CJ}1JgSCe<3~rhmni&5JzD!;YxbVhByCu*6HayD-<+9}-m+G+bU+ZD4Q>DX@ za4LSpM3spg2QazrJ(RZ}m`t2Zst@nb0BfY(R6i>9^-gfFDZ!1{410R$vp} z#%tj^6W%oI4VBL~JWW#+CJ}vM!&`VUF03pT<9YoJI(&}-ng1M)vEgn0e-{`jz43=l z{M$uY23ayZuX$XH-=X54c%zO#&-D2iKfCqb_&b5wIt!P{WB748d=fAhUi62+y%RmuO_A#+?H3%t3+KKc2LfQ4esSL!|=&dXZPQ1gX?s- zIQ<%HC9nUfGWb+=cKTvNuy?7WmS4c^eL3GKM{RD=8O z(YPJgyUgI*=V{!&Kdm!(q0#?b6YnyER~dQi{1LpuJ)}OrZ|L`$0%_;JtT%Yidz$gj z4F7EgpSni_b{uMt!8c6QxSikdxxssPYut{99f3-kdYd|5;}7eT?|6e(U9N#w3_ix- zeZ3m6= zj}7iKURykpFs;1UV|5I)3|+K^{B!3zNK;d9_cxQ zSG}+C)%xV?2Yx8~|7QyPvlRH(DeysPw^5(l_v#2u@$h8>KUBQAhJKf+zl^!~PBnPL zN1D$@BmcPupZc)|Dh+CH8G zmBI53{V4|TG58dNpJnjv2DkOp1cUE2xN*C_5`$NMrWqV-_>>#G!QeJsl?LxMc!8mx zYw+y`A8YU{4W9G42F4h?-r!RWZuu-Tc!P)j27~t++}1BQ8@$hhuQB*8gAX_H{>b3I zFEn8J+->kYgO4}#8w_4$@Usm5u)%u_{!N4T8GO5kzi&xR^Wvs4QD4*IYp^V3vHFiS zOZI$ib*;J_6Dh@jc%<|k{yUfdFbWP#fn&$1>+$NpdN>w?;*rvE3LjU@>+yvOQTTX8 zIer3>BE_*tvs6!u6#cm>?71qIb9JnWW`h2&!cI{16BPYK#eZUvPpwv&&!rJFg1(B1 z;H)|2vrEIi`SZCX=ECZ_1@%jCvv@(v615Tm*X|N4{h(lQR2 zKbAxrmH{|)Tx2NMq2bGRf0KU7C!V)X8;3Ru1SWd8t>!$W+s5h$t;_mRJ%u#(o&z%m`S;m0wHaFaODbf*Ry&> zNwTD2X>-j%1fZ;5!pQZSt~wIn?n1TL$x;KL?vl$~%sn3`V^S=VaU@~E-z=JuTwrO} zHF3$Bn{cj0bW;zmplPaU))$)Cs6yLoB~~{gVR&9rw}29rRM%G5MF}8eHCDUf%3a=- zyeX?`t`N^?qRD5$n%Wx0Qir>!0dKzCr{#4`HH{RgtfsD}vAT9(qzA2#1EI1)v1ks^ zg*AZ%S1oO7)(d|CG*!1K(>^HtjQWb|rmI15(3ANyE}oOb)xtvDEi|gcLOm`f0#ei1 zSktnY0#{TwM;Fb%up)UmD;#ofvL%$&tsu!$9j2v2*kQBJFvPaV+swcX&k z*4%|P$*hCpn2%S23-HV>l+&+M*5(4^@c82TS{J~*&S$K8((yIIO#u~aE@v&h0*JXDX59mo%Zi@D5X-?g*DNojZKTMWiqtqNFq`T zP1>tBHASnHGjq!yIU%g;4sat2#YGJS8tbpZ+Q5U|L8@hPg$Q(z-saD&tC_WU0hZHh zH;zJ$0!qD>F>4Q^XNDdGhOU`|1t(jV6C&zSA7MQoV5BT zI+1a{CS!PpA5)8n4qBE=>Akhup)iWC2`g%v7L6NF4+-3@8VAz5I2p}RPBd^W)(qlq z;Q*g%?u^rS_(_yP(3`CuYETBb17h!q2YI`iU#_Bqhrn>sZCDcRH zf_fEAQ$ziAysxdl5{>eUOgj(5kG`|TR_58JF3UnJ;<3cN+&?AuuS+XQ};!0!|IIRaPP)8d}- zawyL7=@;}91kR1rc5X`ZGle`c&ET83%oxCUXSrh9(>Hckd60!flE0* z7r4{|$2ED75Bpk{&zT0d`D^>c#e!buZ@@!u`;pUA&|f2P_AzX{F@ei;y&`a#t`m&$ zQU3D;pVI{{^;{uvz5=rGJ|ys|0^cuiX@|eSI1LZR8^F)<`J=$4oZAF0%NNIiczE^y zFM&&Xj_X+Z5?t7L`3(t+%Xn7_T;}gj1upsgR^XD)GXgIa@xCSSpuqXfKpsq22tO<5 z5f~@nL0sm`87c6a1upgftiYu_#ptKj9^kulW^#4cTVS)ca;8OoPQsBdwP#lz}1V79F41r5NB?2!O^veV; z{oxA+=ZX4UgddN;3VNx}V>!tN2jw{*KPyjxzz4`9@acm75`jy9xIo}i{vQfl(%&y| zzS6Yv{MO*!bZr*&GF?Nm5EzFyT_*}$rfa;wrz4z=HzIH;=fwh->8ciZMDY2Mz$Kru zZ%|4tC&v(Nyt4!@^>By4XA1g91ia*;nmVO>9KOBtrV*D)LBycIudnxewR4xwkk#gQ5 zaLNCEflL1B$0#<6&m3G@d9D_?Oz#hdx%4t!I|VN5i#f--^fKOTGjQmYKR*RtFYs>* zIoAsO5`q6x;8M=V1uoMYIL?*xQo-kcPH^#g0-q>wsps+(cwFF@2|lj~{BnU8n*mhn zhp*gizFd<6Kk7sf;qdBnWD2}R;8LIW2wdv(F@Z~cJ}Ypk&v~W+MtLs9&&nUq!wnAN zQlEF^5k0tE+?S_dMKASy&M7V~^|oB#Qg6RF)uq1zmsXztInBi<3w)8lW%>G!z@;8W zF4Hwn z;8M;&fy+mx_d5cY^1Lf>$>;gATt0LmHedD#T&DMJIu{(YAIbm5LIo>aruQ|0%Xo*f za>YSDQV*vIT~~B>CHGt)3ZImCcjaaFUR1NlTlgv zDi3`S&v+~r^lU3x`kOuUmj4<-FZu6ELH}L~`q}5I=#%|%%fH&-Uise=II9RN=P?sB zAJWVGDi!!*LI2AXc-BOhkEFjj1wMqGWE@ui^i4ec2B$n%;b-M67C5UEi&qO=+C!Vb zuNL&T3A|R|4+(sUz&8uLPT;Q!T*iAOZ*bUj)$3c|*#>92h*|lIJoGCJ{j?PHGd%RS z82SZ*UiLdS3cNwYJDiz~gYsO1pOt5{z>gF7bq2TT`URfxxIxfMdmcPRKPUf-@U#4f zeDl!wc?P%qAJ=5QQb8~IUoUW)q~(8?hmV!>c|kAvWN{DyhgZ(iQs5UG+$-m$f?o1} z_FJ02rGH7^`aU%{M+S`ff@=e|3o_@W$Jk0>9VbUU?oA^irPxQ|j`U^~>Wa@SQ2}j|6@^SX#UK zQs5^D{5Vq)FkNgaTKe+^{%wJ`3j7j*-;n};S>Q4s2XT-E2ji9Px|34i;{<*&!dN+{ zrNA#qfiDwyli;&51-@6{a|Hcq?DXQG{FmZqp_ z9ON(Y-&81A;n(2O^8d`>*4_?iGT#w1TzYA5ryJbTAD*V^&K2~sJupY$CyIE(Gj%x2 z$Icg?WpK(b<6SFoX%E{3-Yod<@$k3l%3&uThnN5B0+;-UT;S46JRtC;AhG(a75Fs* z?=`qhua#%LpdTyfkLBP34$3L{j5WCB!>?QOs1)>4|JMkdRhE_WJ03n(o_0Ym<=N_? zxB0a*1^o;=%t*md+7P;F&_PbUds8Qhkm)C|1t%AJ}U_v z)aL~Jteh_z+$-lkK`-U})I)FOOr!I~;m!9I2KVy6OVCUH_ju?n|Az#<)Wh#Q^i~f~ zr=V{z9R#l)5(c+&+ITZrd6;xbIlmUTwAIn;|098)>~rNjz8W_;DF1l;to-Ey zmww>8Dez8#OFz(i1-Wbf7vOC9pA}WGikC&!;z5Bo3cOw5lLdaOz-769Lg14AZvw9p ze7+F4l>d7RK!n5Qi_OPh8=QKRV!s(mD8ogK|nf#|gX&&uqL!0+)JtR^ZD8{VN9d z+SS{FUfR`e552XkPg2llT!qMRQ2tZ!vvRHwxU`@91hR{v3V~OF!pi?QfwPHc@ec(q)AgmmCH*%zn1zG! zO8v|eI9;ISzfj<8YFT`Rz-9e%VjYNZkiWz`1uo@TBXBAIodTEizY(~U|A4?*l&zd; ztn6`69x4Ax0+(`jr@#ksunY(JNO^JvF6BQ(;F5m4z@_{*3S8>HOW;!edju}!UviBS z^C12IL*P=LPXsRIPp5I?@TPZY3Op|bULiC!&@X%ZSAwe(s z@AuHpG4gyR=q3NduG8|6j3#XDp{PaUR?Y^)r_A8ImG)EVp>H?zmk4?(XVgRAZRnSz zpug5be}|!8o`T--(Er-d{~!hZt>4kFOMAOi z;Ih7ZTj0|E(|_*rk^S+Yz$O2g0-r9@wNT)aPou!4{a-Keh~RTT;8M;Z|HqY6;>V@H zZ!tK_3;o;hG#&mSK`;H=CJ+5oL;qX~`rq8`%5x(wt^Ir=aH+TOdY4}6;o=ndf)sf0 z9+!{Q!$m3Zg(>j24er%X`Y&AmQa^r!TY9UX6H?G;{L|L+T2^0`OgQvbgdxU|FP1pWiTKkHX+x>$AFc+V2}B?7NZfiDoa%*W*^@HS*RK5kBjhX=_&kAMm;zrUaH-GM6nIYx{H_%EBPsBI2weKlj|AQ%hh8G{>i_0amoMO6!=Mxx%AQw z&l9+`!>SZ`v%sYt_N2gnodVyM0{=$}e8eAI`RC!%mZNi0;L`;z?QMPvyeS2KQwsb? zDe$KSF753_flIsEl>#6AM>oCF-UdDH;vk7Ykh4;YBI%rWE+<6!A0TwL122XDH#q@VPb zi*qQ&>fz+KUHnXeKO*q)0{@r5W&WP$~{jEYjnf)3+5~pwIOZER`gQw%} z2K;P(O%nJI1inzECnZTu- zH7W2720sEkhTvz%6W$Q?vVU~L9uVQ6oYJoDOo89 z2QHu61ine&qXqtf!I>_~I_E?D!_j5V#BRsW%JV&e|486R{S!AhNMDAZrC%WMbprpc z!L2^+{uDO~`l|%}_XR!U_|V*6WHN%7)Wgyg_^ACL#6kLH_*pq8rNEbeL~3{bkA1J& zV{r1R$ItS~{gl+2zs#@849@fp!tY8mURNXN7Xi0?mI=H-;QIxBv%tR)xYWa`pMeMm z<&^ny{gDb*cm$U=-W6FcK11Ly3jBP5uQE=A{3U%wzRTxgLI0CcE?y(>rA#Ca@{#nv zW1+&~#hU{zF4Nn##Kk3_?f1$Ad zxdOjb;8g-Y>to#DAb*)(Cw{8ngYdr{aB(TWM%{0pOzqbQeKLzWfLcA9aek0gGszF+0VCu)3y2Ujl#@My0Gx8E%&%+%p5|C~~N-{8UR zzWl2^xc%OM-5=cYvHSk-^3Ydap!p9s`ETj%KG$um4?dO72}j;x`fTI%Rq6XG4{rCr=03+fEPd}{ zeZR|t+x^hd{EdR<@jfXwB-M`!V4@+c z9^8IkVMw-4pXG1AuQ1Vr+kMO{J-Gd@!*UO9_e0;{!Ke1>__llSK7;4@2g+0RQ+;3Q z!R>c4dc6404Sx@Azekc|Dr}oxyAOV)7yrHH)8oPI{^{F2xZR&UXXrrr?Y`=j9^CHR z-r&LQ_eFX=xcz>~77uQ}UozyVf$`dX+oyVP`<c!R-rdGH>Cf9ApM_d;@V2d2w@ezc z+da75?|!!jxBK1uju|MY-S2+52cPzhV+)Im&M7J$H!d&loWgT}=>KC2 z3(q~b2+zkAO`NDGtBz<7MW&^v(c@U%oTu7X_THX%kFr-j-&A!u6=R!6_yThR7Y8m1 z%)V$=_=fjC!-KHXmA`@KSXcgT@C`eU%u z=wlaTZtlq63xq<&&U=)n&V(~Nzol*VAKBB1#5y$R=;z_sy8QJZ2m|WFqwvOe(*w@F z_%-Q4XKNr}$#~@RSKvA}F;M)ugNwFDgAkO_#G3P4IzRQVntul45pk>S zR@=^bRL2QoL=-`UeFzkZzE$ev-WiBZ4mexm=OempVBEITG7TuP1+zz(43PL&FULhV zc5nVfCHI>AsXVU@Z`_q0jMWbE1!G0&rSYsWA!m2Uc|RDxCJ`$Br2VAw=vRSQ?&HDY zZEZ)CNB0I2eE}!;;XvZaQ1QoYZ-qwfj>I&p2w3+ait^~If%pY!0cVG^J>+EG9+-TQ zuk9vhjY@MQc2_>T@DXGZGXa9G!ifj9Tc||SD#fGa#Bpp6=BpO5QcPfTW`|1~wBQv)9#yx=iNe#Lk4j`}=sH6dFc$vwzK;3*#J#zQ@d@nwXM4oXa=Gca-k&=}B@>TEtL*&IBJXI~(8 z9(%$w_3ww}H%v>f7 znNtxhc)TPL{FRTn^p2IBA|PvuzfhUew$5ZqN-6xSnK_oNwv|}(AYbRFODEfG53HDy zp62hk;WVvMid+$W_5675kD2HdQ*zS$-KXK9kbyZ(IbkVKDWeF*a@U4BUkLci_XQFg zSyD6}bhflDx27G0CKPe!R)5FCr!wpAQUC>P06&)e^-AD1#>hL23LjG*pnT&y$g$w* z6b$Bm+_cdnPQ@>eX0(gYj_0NYW2c5X-)Z?Dmaa-Z!FestAt#6;%YW7d z1vAp&WR&)(wg+vbRD3TYq(##Y24cg4qc$Pycj9L9Fn?EL9>COYoZj4?r{_8W+4N`7aerJNE>q|CA0?4YwFBRk~0r2WhO z_JZ>0`z(@76U*TioGYRu?t=}VA20ezBszGSleHo-n0EXU%S0a{P5KwcQ2d3zdmhTv zKw~x@LpTv=S?K%`#N+d?<`)^MT9pJQY({#&Xl9#hZ^xK=M%W z{`S+Tbc$LYeVuw$9zwaqa5Q&q(8;=`?XMJ;I5o!9mq$ORt*A1M+9Kp+O@ZJ2CbUvC z84kBBo;fBIZ%|J6g!1UeEMJCgc{J-`q#q$}Zu`5N5xNjnL^qbiM%-AEF=9FVH7t3z zN?80P>hW0$M>%O&G@sH~?rN%=Qbgh%`R{|6X`wo({$0eKV18xTY0jS*b|U#BDG23< zem@4aOqSA`)0#ho?0XffHKqh=SIMZhFi>2}6^VCgCWxBWA4XK+urn`zY6NTwBdBci zBF=*R;bByjIT2@sN)5_tmy$G?)|I~;!9t^+4UKv(ka!9y_IDqH%(s;fDakm1B{#M# zXar@#-#zr}M1uK2nZnUE`O9(sBYwWIec>CPnu>}k?EI5)S5b@5h!$Vn*n%#M$T)?` za0-_vE0^^~mCU?I^abWXFE5SlmT!CuEd^HHs3BDUL{}QB=?F+QwP@F{*S7m?Ax@T0 zQNgXEh&Z%izoc*IS32BF>td9o{?)hO$=I!9KeZk>65U@GE7%a~{GjDBc-7AHMj)Se zz#hn(61PBd7;fjM6og>F$$ZS;`L7e;EuH6rNE;)g_E&)twn!uD14Md0Ds!4UeQ2y0 zzqGBb!zKwXo-%`uX^KSGXOGqVdpuN=koK7Yq2$D`pjJHHtvy!-CsaIN_S{^()a+1GX@bDWk>8CYPn zS4PY|j0#5}HX;MAVQ?T`dwe1gKR;2tr+sWB`UK0UDjVR=fMv1#n<}F3Pm5*!Vp>Ml z`am%%u;UPU;)&utZO?;Ym*(dSjs3u|hfTv$QK}HUJo;fUmVXcG0e|J{)^JA&iYQsH2f!k#EwMvogl%(#VJtK* z=58+oqS9emtweqjLSw7}sXSZ^nkqp@Euvo#dfwcF6#RWM*Wb;~; zf<+h~B6r>ek^FaXj-Z>eh=HkGra>upREJV#Xw*~X8~=e$h^8%z&l{OQZBz(@A4`zd zhyFw$o;xDoyo$g)^_f8<~N0B)I#Efg%-#-KZys1gRVRIx%poMS~R!qE?% zj{?re;ds%n5Y`vV8W)Jwp5u!LM~o;m z52nY9?qlL;alzs-{*DWVq9i`$d|v#owq5X3q2hh2u2?|JMCMXtXlOT2>r_^UW35z) zZkGq0Cz57~YCRasDn^YysVttK9f~*Sqs8zHIQmy}NV6h}CQO%U6+EcYgbMjqvZ9-) zi0-D*G09fp=x(77F;y=u5Iv2dcw6@&Klz+=731q|+k%Lo2L#H6{Sc$o&d$*~{^E5?4EQ24@ORC`!;rHxFbW3smk`_+tyw?H z!6QUX8w?h|VKs2TznZT9$} z2fqQvEGGp+(BaQ2iO)L=rriXa*~5-=Q6%~{bCaf58q2yn65VlrJorOjtg!Rb=EDPt zExON|cmf5X?M356SQZ)(ARL7Xa$|7iOb#1q{?1W|FX()9;KdBn=`G&r?`8?5{K|vH zkWO7L{axo~fqJs8v;7@^AQ@^_I#X6oOm2B}ADaQpM~ECNxH*tfu!>E{f(P1f zYxwf$dyJ3CV}T((ZYdE}%X7df`UM)ftDtSAVkh$m6y+g!;)~BuL;ki;4M#sB6Dljn|B-74R}}rmm9FMt86vDxu&< zXbrkj(Vm@b_^do$dknI!Xjm||#Ao{?!C2<1U`A#P))90<5bT3?NQ1U90)(TVB%Ugd z!ddhMi$95FKI~-vr0p%rx(ZKK?*uJC8bt?kk|}%%Qk6$vqhKVVF;FkyM}cSzJO`ZS zAERVv-JG|3wcRt!5kcb(}hSVGI6$A2qxQg}}+k&=^dU~`- zb*v}~c!%K%;S~xq3JMd?l5@d?wygvBY)1sJA?kf1!Z4?m5yqyhrbg(5&^*J48+zIg zftHTu$e{CHAcLLgJ%Nl7M<|mi{;0i~La3C*i-v?Vy7a(RbPr+5lX#*cUT|MU^djGk zXjTuotBk`_Cco5~0v#`b1n_x`HIa1>Y0+Bk38rP+N8}%j4GpE`-b0Vot6jCfd!ni) zJ9M`WEVqL$q)TDeft?T8Dw!6`92#^s!Jp-z zfYWQ1#-G7;vV?!}s7K&v)8tUv@n#&|JcN0%VqED4N zv(aN5N&!gCYG@lQuEZ&F+8(6{MA6R1=oqUtc&w~pvE$Gg8fwc8*?drn%ETEqaBx>_5<*EN`~2rUlLN9f=ohh_Gm4NRrRux{`#=-$(b%0vX0ANTn;d zE&xFclFYRl3}dh)9FFVyiTyH`q@+heXJsnW%LEM=!6D-zVP^{ZN{1ee+k01&h>Y5=obQLsdQCOt_=_OyzNiiRTaQ4IW|dd$E#GVuMl zMPT~>is+vbe+nf2gs4`-DloK|tr`XX?j{rpTR?`OlJ8{in`Vu`K4y=vZSwCR1$1kg z2Cl=)_gCObOb1ujF-w- z&L|=BT%5xgz$7E4h*5-{H&n@FiNv7g?ED;Z+M+^gVK~G&B;w>Muc-Ji9=yD=#iivK zJ7{TJ%>Cc`6cXL=1Ba=fy)Ay2j;^w={U=y`&B;xO@Iyk?|uRkKJZE~<3ZJ1 z=Qz+V1nZwfoQ>TN15OrPi>})fnM3>ce9YFYc00`11|}o=O3=yuLH}GlV^XK8q&}uc z=AbV9%FeuHK~j-Q+eLQ=eAx=+nDRS3!;=iLs!;h2kjmSIv-V|hQzPj~FyLED-4$pJ zg<>aJ&G=UxK(1Tu*sdA$OSgl%FTC+>zPdaSU4eoT)7aMyp%L9b=p*K*e&tXeMQLQ8 zX~Zr4f7*}4ML(k7)KwRJ)%1At!(SOMhTHyU_8}}roz^IE1z~x-`Bq7|3WQJ|>EP(i zu)DLeU#n6;keq))(21aKN3$G10k>x{>@gE~*4Brh4N72{Qr4%PN7hp#BV5GIVf9_tb zUPfLKeGd-z*L$8pN30}PduygM#(B2?v418K<~{QF8{1@OFmil7@V zh3v_K*=pn;YUIazqFmASU3vjs+D=7l#b2ky55$7U_>u`&Arf#*IJ%FCCTEiXC+lG) z{|O&ZI`l=g{*bO;?0Ggqa$U#3wcOv|^S*K|bOHTKaZQEM^@O84&`a&>m%%3e7*tv$(+7;yDFp*`@`o4-VPnXJcY{hgP*rv?8E5eH&Ej16$i%imoBJW%{( z&_7d;Rbl%T!FV|u z#IH~VJ&ZB238Tyy+|pG>d2}0E+|HC3pD)65w!G1|NskS6ax-Gb#iu9y_n~LLH5i|f z?mUM9o#Ots4JH;-0I1DM1_g_`IG-P%!lnjVAXyV*1(QqS&EKG~N!jWk+ZM`p72E0v zw1t6DFm*f5iUvs`U2FD@e*2o~=^n6|v0qAwU_Xh4im_7q)8NB_M(x6G8unz|k^j zwa@zh3LqSvm*2qPdlB5e8v<2Jach199P91YH?|+gqPiPYaItD690PV`#RVIh{lOU8 z8|ZJeJ&bF0#-O0i0D)Y`$6=v&o^i6bje(S#{>A!+)C~#xjnyFZhbm1la_xnG1 zo6%rY2M_3;8mKTQ_m};@!~-g-4-YU0rT>bzc#kd@?#myYF>`iaXvWNo%70%L&Z`Jj z%)GGtk#Faf&&Zn{4uyZ8cj3%AoHAD7+&mQxrwZqGeqFl4xv>(ba_9EBI0ZJ}ScTKH z@C32iTCDJQ6*Ka}zfTJE zM=M6T^J5+P4|U`Z>Bt|_k#~y7J8k6uJY?i&sK|8-vHXV3WJ=dx)qfdeb6f8Bnio5| z(aGG`s&kv~K_|j7fuTrIf-g7w?|z*=To3I=qM7N_qa$ugU|6evAs!5vUZ!4kwp|{0 z1d*!@q%B3F|6m=q9+w>1W%kjmRfz=|x(cTr*cplLoe|HvKNK5P<`kS3aK;8=lW2VL zX&BLbjxVe?*m4-eE3Xz5Yqqq&#}`=fRl>je@>gk{yJ&KZ>A=qL+SrJjI{(sK49Q8# za>63c@}}aCzJNY?Fn&J9^|zHcBW@{)&BJKoUzVc1sykWeCAHkk648g?vB~{k?o1?b z3q17U#S0eH)FnBJ0JK&d9{OAz4V01Al9P4VkRECU#}xcVs4M+% z#7KQE$<8Us9$u22SCTz4kX;zao>-Q>A$`SRD+hNCif49btY+@Pg1m5bb6#X|-O?8Q^sJ(Bm{2*UY1xwI>ML+=Zq(;R z_NuX_wt7r+O-r+H%!2CXYTuYEnworL8tZvO^08wk;+8};i{>wEtX@*%8&g-`Tr&m| zoYmA^9lhE&CR)E_Nljg|mhb=be;&e9Rc47&lG{{sW%XqrSlr%Yrh+fi-pI3>orgX1 zO+Mg-fr@8{p&4$@n4GEb40CT!^GrV3dwcfARe%TN`QL^gi?9??z0t(k9#tlOjugnl z%5RdTzBA5iYc7^{uL(cb0_JSPTX-riylLXI4Tb!VwQ2g~qyCsjHoV1W0yE3M45dDW z#k^kmz{+hgE=BWVd}hNJSweI6(sFdct9z2Rn)nx)aQ5U4&wH=#NIUW@9b&l&kcC^k zcR48i#10kz`Y}5EEPYD;_r{-m;JF}Orf;9}b)H9v@6cQ_4k-!cJ5&x6ALM1N?lTT5 zjhZYYnfigjGL&WpV$|1BLQY$bF)hZIGmuo>ot6S0odTy_9E#7kQsCt&a9?tgd(?MD z!~832>Xt05pI^6tH_=5`qcZU|H8d`+YhFlXNkb$29xfW;0~;Ef6c&x*l2?lwn(7;k zTik651#OG(wCvjM^GyLFCbeH>aMH7^S^6acr%o-tl8VIP<^O=GY>4v>wxxgRL{e*d zyf{zdk&_gx_}~qF5?`7E|0>U=mwe7UUE?-g#(nrg2KT1xLV?S4ReShUX|}#af?n!p zslX+l)9Ki8FkXrOGzFeVVjL`43}X*t9(D=De_jJoG;utZN8tG1uYuS?BR9uXbxyek z!mM>*a|)8OV^hd88cQ1xFoK@JdYs+05xP+x!Sh}|N5iZN^qW-*1F<2=xyq~Xln0u0 z%X!9OXXPX8JG|B4q37UdKLW0pskp_zdJQfXE?n4yKlX0J6c4RE60jrrn0XhdM|#xj zxy_jjjQ9regjVliZ1rx=985Tzq5EztCMH@3YZ=&hU4&=0@mdkx#ffbJXS=f0{NqdPX5k-^LirjuJ8|HJhe0*KFqIHlj(Hf!D6N#eDIu&R3zwzcA zvjKBY3OIkYZ)fw>G+f=1$6UGT(J8AFc<)vGNgG<+dY(D-4Ec(;DGA%Y_n!pvul^q7 zh5i_`D;H-X@;%iQrk?^~YJNtVzvGHisR}KldY_!D-Y4VfFwD(ATs_r&&_L{Ph9yhr z48k$j%VN1d16$0^@5A^VvJf^zJm~ak{Uy7bCIGtF{*K#Dfnt&~PVD@Acd(d>vqDk5 zkANd5eb{L=vExUN$PVC#q19b@7MOe)X8U}S=jN)&DKiiEh|aBT#b%|B9#mv%`Vcx2 z-Gq$qz!ft7$bhpKZ)wqGMq=79IbZiubp9tN+R`K-BW?B(p4(@!lR?$!X`p!hh`FC< za_a0E>^ZIF6KJ^-XWQ4sMDW4*r3EvN!21xbJ*chiAsZ*ny%)^caia!eX9q_;i&v{V zaXtA=f7i_?LjV=MNUge8Md@A@RL}Y&3nQJGnolWqQkrWxz5=WQSrk z7}j~GWjYJsM37(r{cxv0BRk-Hz=`>o$kBc_?5jNbG84U4B}u;_t%&B|3MlG{{xCGX6AoF?a~kEiQ>Y3tb-V!_d@?c-g!X zVcB8bjSTaz{u!!TIzW_PGl#~cr6P)#gE||TGrK5IT)(YHDO4{H9wCN7U`)_&H52r$ zA7XMSmw63k5(GZI%1rD)bA)e)Q%%p;MZv!HwF5|Mn!bAL%enD+=7r5XzSkO|M}#?R z^nFAVOw;v4Xw;LTQBSKkm>>JQb72C>G672EZruW*0p(A!)N4Kr)KX+KVr2%a!Z$oI zHJz#Z8^^>KQI#+PJ(QwuY+)CcWE=wqD=vfxoy7?pB@SG!(pMzJ-Am>Um&y-m8tY}u{QUoc93f25 zPYzDHBa?4Uixu^9hV&|O;*fu53Hr8p56wB8jEgqh0tPVWPBjKdFz6Kgz~A{bX1xcU z&B%7fO+~FzggeQ9r%L=?#@w>h@F&wnQoQUq5_Q^;(CDJ9P`nOfo*%SLq{gVcis;K! z8kKi`d^V;wj_dps)3z{83-jxobdGxJS4ffQrzm;%Gu{m*vOX~9a>C7-zrht8P*%S6 zkDL76gJ3XLwblqRD$SI$7*WZb1FljX)$_)n*LCECgJq{d#RFr+8IkC@F`F~#WH~i~ zq=%aGzc4w3X3Mf#6a?ly42dH)A{}#K(lO=#L`;{jP*eWRti-v9iwd2JGv~`xME{D3 z&}*k<4_$O!P5Cdtl>ZO>-Kt`EOi%ewaLWHW&y;`l z0;pr(aGC|^wJo4!0X`4`6AN^f#&UB|kB6Kc{#6$bnDf63bN=-L01V+l%}lC4{^c=R z*}UU)AF7Pmy&Y^>uqW5}+KZqiKJR>?d6XSKoE9sse9au2a#F15 zc&rB2(@6atod_6-ZpO>P8#%Y}3fw|-TJ^IL1}4ZN#@LqgjCuvLv$=dgFv(L){#L@N zj^y$c=HG*hE~9o9hvKGNZ+sQ5v%#!gg`_NfoY%n^7@Iai{pQoo^}saB<*^aN0}wB}*j*|as6|vnnYno1dNihwG~X};`udn* zKW!ccI=X-Q;|-vTL|?&R?X8rT+?nIdoG_+IYQ>s5&SwIud#)oD%g=BHXWK zY_WW`6oPgYblwhQDwbVJP%sWN@(Kg-$XS><@vO5Au5$uhhZ=Y*e%X1xy^ta=LO`{Y zfc=+4tR~37fRnqLfRpi5#dZY^-&7W8-|vR7Vl{!Xmx)TGKP6icSWOTsQi};f@yv4r z&L>(Bgeu z?oGHp1v0AlGRzh%CO8#~2~NjFK^~^3of?Q2jSR*YejP0SJF|l+2s&W*rd&|)vR#~l z2I8&3;=%row@`ONA7(*;Ua>b-d4VpKrCd;e_gi`jHgk(=fW)*Ly`bP#yj;S90!;S| zInVl6bHhs1Jl5UNNzmlfLW<~q(|1DaTy=6{MMI6XqlU>5Rz3k@(a-EeP!=0nIj!DU z`OwiQC!7}1+#$_89DUBl2i?=+Q9-U!?aROVyBDftLFvGiC!U1?kd!MIzJZ4!=k>s- z*D--46rYV5gGP9N*RvRzVc}6WUyQfny6G5lw)t02LL&&%TC6S72&gi=8pOMHZS2X_ z3%dA~N4HqhLmNi5Z)`&b#UUH@yT3F(0yFu!c;Rg}b0@KRiuP#~)@T~Lm^_EYH|24x zDd#F^E@9ZJyW4gNgZ2iLM|scaYq6|5gvQ^@qQS`Z3$OaS`=KgItvqtfAH*E?U4Z;u z?_mswGa2Yn{T-V~hILumzv>y&<B>g?VRsaVn&lZ22kr?u z!H19>tpLcUcZJ9--kf!mXA#&w;)<8p+=yoONmYqYA}2;=X5TCHO+tFns!>R_(&#{f&eK@Oa9U|b?x`iQ$mys?IO+i* zsXBjWADYj|ayI>Y0eDt1`~#~PevXF5yLe=6AU2^`FU#|H?HE27(J z4ZP&+RA<=ro-fWSgc#nJh*OQ{b8WUaMvv~z}Hav zT?omo0Y>NF9xDE8&^guLJzmX~bG=W;OK=qI8)zqj>>h?drvIw61_`uMiyo&pr8Hnq z#m2ByE+e-vu?@_f+_7A`Aox6|()tv&FcD#xy)-9aW!69(E8&v3MaDix*Cv5zXqQ!d1pWbgBSr7rM%$XEIhT zJ(n(=iYYg}YUP4@uoHB_*eRj3e6?`lF6*r)(OVJc0lGs|=uV7qay5WnrGpX^{TH0>?*^_0*rZnj+|c$rO2$@WIQj+(yXuRfSYWBz zSaj#PYC#tnu3Gpz=BMB3u3Dh3m==ueVtK`%Auq&!F&MuNV^RCtXZA49wIBPE2BIQ~ zXF(9mlgG^RHK;=RYjXyHx@%Vt?pr&zSWA$u-q zGz%73%k2UkY#wb+v&cd(T+j_rs^<~Pj=`ELrg0)}D2tMkYZRb*TlSbpMy3*jsl%A@ z$fXJh)r-twGS{oKeOob`yGE#K$a?&T(~U7K#aWV&j~Qx*usGq8)ftDd?7{^z7u&OL zp~|dV(8Ze)wr#aNJCiFFG_*o&dBbTis4Jh*PbjKoQ2&qAukfo)s)F_rJSxv6InQ&;OD zHx_4Mu)(&wM;9F%j9-lP0I!AP1#2;2#u;&0u;Y-AD+2TYJ?0ssj=Yx~Hh_ap6kG@2 z+H=<^of%fJ2-YW{uYd)QphZFaB?_W_=I=gTEmU|+zwm;2hCzgdiPjKfhhg^dVQMk_ zN=SdZ2;07;e>Y|YGmDs8sJxsh5A?Tc5A+fw>958$O`h2k!Hz4=l$HG_>*ufYc_yxH zGlz+(1YIaL7&9tEqq#H+qiiG_`x(i)RHGphJy7ao-QRz&T7J-_Y@gQ3_~?4~QWBJj z<%|*&!^6(k3_6#$fEj}-Ta>z2h0$e!OMY@VeV8$Fs1$SSu>^sI0*>SaGr7L1C6`?_ z77Z|^d+lGHV%32u+|kcf>m7CXqyLw^cY&{}IM;_)$QFV|cFFb7@Ooo!U>4on~;t-`_gXOAY%afaM-g2`A;@blbqg2~x1 z)+QWk-2puY)*VdFZp*js;1q~auR9>a(h|-9<52d%x`RFZsD>3^6|DG1oq_QVtWWiZ zpo6N$IWTgIPlkAAK0ZcwwB94%4pPXn52=+0>r`>aDjj_NKAim>76hcyZ@~WlhuZ%C zNB|93KyV2A|BcH2{}okI_1G0G?=gt>i|oB9fUFf*05M*S3U6I@AFb^5HZj>(loh`D z3QNC(_dm*hQ@>Xw@T=;5ZrWREn9&W=)eY}xWIs@%# zp%MPnz|;rDy$4MD12Hw_{hVg__rj=xWpo4Lz$Ch!gxY3uX#7iWdx678G#-@%{~W!ap_W{ zM|7};023M*YV@`ja;YnKyHR|Aw5i>>_;ow_l9!{ofaQ1>s|^-7%m<*?wGvf0mk8XN zOrxi1tO8IyQnQuSdud;+A4sML`h#z9z31G_rG318dNDzK$cwReT7PN=fEbvvX5Bg- z*WBWP(pta#{1F+o(gAj*+GtuWY(QK2X4~vcYk?ULL8fdW3AGO*+m=k}-97C3M=8s0 ze3jMsA25;|L?T zbYO?lsF9hv!{bWBypK1&jRgd$^PKq34->IX;m&37EFT~o5*2#|T|ZP|coj@g1lvu#_Q=#dfhxtr@8`j3m*}f_ZlJ$h=~@X90o!I3jO) zC^MBVZO3;J_o;G_nX%3K)8RQI995`51*-^e%GRm{1X}kH0hN^zWN+zNKw$LJR|^Pa zzXLrW?|PWB&A#<}R$XQy2`tP50ovzh@8Ap68XG{6b5q&zv~7ovEdUzsA8Sn3lk3HP zyy3ncTk%K4WIg5Gpl2*s&}uy8t)bO;%6phr<6SEz<5yX%cdgJi<4JFyDjDqH>;WV3 zu0k|N-PsxFG)UCR^%8Z%eG+x@kwDa9#O|$N)QFQ&C%uOQQNPtrGar?ZoCW%f>=#hz zS$ZoGwbVW`UJ>X!UEPK8DSp_o@}zkD!?Rt#;iIWr)8&QZ($Sxf=q~<2wgWG;t&bW{ zj8ACr{u*y;@P0iZF z%liy(VRHfob$N7s1vR8GsQG%I#>`-NJQ_QdYM+b$6}RE#weX(sFpH`D>fgrnOZe)( zIguGW5DSA{4w9Xqh<6sicPgzS#YYs(-oH7*3wi!weCzrO$E-^C##)7V8rMv=g}hB~ zJ!;}X3>X=^wTJ7@@emo-Chgl;;&Bt28pbA4UZ>9PpKDE9sk8fs)U>4cbE;a> z`_&9wrgyEJhs!0GY+gAZS4U|a<=$+x?aSm-Cp0^p_l3oUCKs}&1>RNSKClNblwlRf zaRo8*aw@*hKyy3?_nT8(aiT5C8q!tF?HO#M(2<`NT|{MH%7Es>fw^CU5?5M?>bQ15 z%MpPEu$aF()*A-T=!5mgXx-`zhp1xD>FjPh#d}WYZZf^8ds8x9yi&j5(zlSm@ZQ+o z*4G-+13~469x8rQ#>s?+c5jJo)_K`>nzuPX1qL3=f>gpCvyg63dKpR4R4~wR4^}V? zhDs*WN{brOr8i5U;%o5@{-=g?rFjPvmU}Q*a5E5CTR{=-X-E%hOc#vwvFky+py|6z z8#<+(Mk5gorjoIlr=mPM<6^Zd7K+9mbv3`?&ef2I*wdwzK90rG4+)OBOKgmBVne}O zu6HIymnb{~T|V;=?>@p53l$JMzCG7=DyBXBWjuBO+{G9G5WAA8A+Ws|}HsyElw{-eA)r!QQ zlq&e0Nq}4US(Z@!8r-VrG(+hBY-{@*xgCNzyp^$vmhpzuodHf?^OeSQZ?08W%}8rU zV|pMfJL+r-6-^B~z}F#X@mbx!s~^(rWZUs!&CV&tkG%m}N;*^D`Zo4w!*tVkyn#VD z`z&f}N*LAE|3}xJd_SuB|9jV-l*9WZ9Yp=^py1#TKGP>LV9@G9cR*xC$Q@AT4ybHD z%&EpZs;ju83iaK=@mcF!{(rv4cyk%p%ayE}B_X#0R)R z`r_nUV(g!n522o$Z&SWwz|; zf0BuRMldk$?eKhNXTWwvXK7@Wd0C9dQv8ejMSn2OcgXnHGGpPc)t8=MJN}**)(!pr zGuF81a+1>sxr5CBWEbku6~SRmrErmp;B2$$pK_xUJc@hbB?`^q%r4@TF`f878~4OT z-h$T}d@w!33C=Yx^dBJzC-_L*6OSr1hf}|amsvO;|8K1I83#JSwLa3$Of>jXv*tqD zgEVlF4Q_kfRk%A8-jWAz1I~EwG6|OU$;;zk*7{VWotYJt&b&D-l@(RIR8X6;+j7@uQau@$SE}R%k_EFbv0H$R3ld z+4+;fWlatJ(0v^6Pu&#%hnseQbhyv7;OD|Hk^ddqKZyUq=oR^qGDe?!EL`MMcxsLg{R@7)g$u2-EL{8#vvBd>XyH;H{fmWb zE*$473l}=`EnNIBv2dZ^Zs9`b8VeUXH(I!)>j!yo*VGS`b5Q# zUoBkfnEt0}jwOGkUOw8w#sA59@Y+21I13m06D?fm&&Y#cZQ;`1T$=~~ZXW#SdGOaP zT=;q0!lixcws1+;(WZeBd5ZrNEnM2ON(+zb>~PMr@QA@j<-t=HE_7z*!58Mimsq&) z-(lgBUf;sS|E(4-^1Rc+#sB>lF7zL@aPj}7g^N62vv85apDkSE`FlSa^5CagxbT0Lg-d#eS-AM0W#PjAdwOmX`QoF=%(eA==RZ(`i<&z6V%3H$Lnkvg>R0FSDLAX-x0Bvm51O&39Q}PS zU{gUAnYXF+==RqO7M|;0OTYUz;m28c_`a7s^^Ayhj3)kG)Rm97p2;8oTR(PAU2u3$ zU%9~ASA#k)dQaBb*QARNC}}4fd{;-nxCQ1a@Biob)u{S^)xH`}i(t&P-g?eA=CHo6 z_PEFR*WXeHe>1Ylr4riTt)&DH;X)S1F@+-h|D)majX6mCc6`E?ToZ_!_td4J8)Q5* z2SMDE*PyG%gB=Io)8dn^QeQsxn8Q3_(1e$Z4d)wkknq(K&|K~C`NkY>Hy&sFC*kSM zmK}qPKTHR#F?86M>5qSrpVaxp?7U~lRYw2J&<`QyZ2kqeuk`oN7;_*W|2Mw1DVN~4 zw$yt^0hfLT;}Xa3v_s*a15P@VjYp{;9o>kj%`nuhGu>=|v7lw@+=VU9qPb=l3>}bT z8g%jvrk_v`n;Yr?>j?P<7-ewVe`CNu---X*^Z5Ts9{(Eycrf10dFVVD@E?qqV={E) zKZr*N!cmWc`dv>DPVmX<$#LdPpOS7_Ff1+If}S%p&pvdYplVpWO0n9_XH+n7tyYA9?dT?Nr$}{;F}Y@tj#$oTm<%MXE~V@(o73YQeMDI zT3|MJsk+Nd?!my1fwUnf$-xIq(O^H5^j=JP?<8r{29tyx@YQ7seeiBKaFB0`&eLxx zIDbS0y_b2@!KJnI1lCtZL%IFEr*vrVlxsC8@c2gpH=m-eq$ zWBY_-j>f!j?Zo07-u7iPtws4M(cntnXo$EUS7ln;g`+^|QhLe`HV-THqnf3EW^$VcW7F7L2u_fqUcO%a6y;z~kF$w5bM@ zh5a&9>26Q;3rG2bABM5rXJ8ql_%T`Idev(TS8=Qo(vx`EahPUP6PSwKaOZg_CP)Ye zwjd+LFP4lf*4v#kCK$l}0@ji`DvD&JkDV1Yr&!=KT+d0u9ux-Eum{zdz5FZ4E~I0d z78|pj!q+p>>8&)w9hTygO^_{$o@+aLBYD_wS5NS|ej*~}fpg{9n0Yp$WjUGLBXn3Dp{|2SRhfg) z!PPJ$DQwJy`fyVjRuWpr;G+hNH1lU*4W6j3;}%U1PuK&g{EA;(sAt}TR1~2FMYvP> z&gzZX+nD|f7RdjV!4Ai}R5bY;H=2C$jo(a)CilAG5^2)qpriWNhz~_bhxB+8>y&r)DRwtQ_B=Pm>YkH8P|{r4R`%YZXwXoiKt+{ zsY)3asU`fD^I$D&=-a~JU2JNST zwlN^_mBw(h({#0u&6)#N&C>rDf9-;Y(kM`>8V>_?bAkn^IC$3Lgg9nvbW~ z@K5xfTMe@LMlTrFHQ(^$P3{)V`b|IrWmnaPm=tD?pVta3PjT zqIgrxN>WvrTr{rtR3f%9;dO;GE0H%)K1Cy?3#c-*ggGNb&IXuE$qR}s zW#JCl(wN5fq~N%3U!M*rNHeiV!C?nmAB`*E34ta#RDk9>JN zI!F_voA-t%y~4`yc-A0TlPGOFD%wQtmryNVdjRJCN~qX+1xC&Abw3!E0i@*BYU|tG zgw#uOH>p==Z$YHvgVqaNU)2k$>Sn^Jv0Tlv9#@YfsIZmBG^B@M@hfa_RRYjAy57Np zd807Qo7xkYG7~|#^9pu6bhlHP<}rWSuTNx}yScQ zjs{yrhrRmmWqk%_QSUQ1)g`6hs_rLqt{M9QY-sSdq`WuOC&0LL(=YLDP>L@A-2+l% ze-~yJKeL}7AVrUmmQo5MBWVs)Bae(x6`wvDtPq(K=E_kviFnl?S;A%(|0PxUZ)8jT z4z&5Frlro}r3#;Gsp0M5mN{I4V|LK8D=CMU{RAmvb)XW6o69${824c%t*zjUsKRS* zMcyXUDhjEub>BDcy_*>Fn#ni6_$Ru!N;4W>bt6WE*oIak4wGuC9^m6I0Lb zXXY#Z+58=Wr{*F;MXl$lv((w-;91uonGoz=v1|=O;qLf1p=8Gncsm)g^f9y>152N7 zHTKP>U*Kjg$8v`j)&%QRILT1SE>lXAUUgJu+BjseWUD$Qg1K0d%SCCQQH0raBz19> z9vZg=LhJm^Gb$P~*jQZm`TT+0ivTJItAAYvmKWy)%>xWf4*3PJNtHY)?5jnGNKoe} z>6;v8W7hc|U@hTfdJC4X80?v%^+0cr#mec*M3fsg-EKb$zHiEao%IXb*Cv`9#Am?gyTjD0s=0##{x9<4hK# z2u7qJeyk$y77kv9B@0@;rMguou}Op7C=IqQ6C==Wn-&}G1sd$`r`*^ELtV>O3oyL; zM6}gfY`Re81`}4B@~?LgRLx{JR#_`%b!hHmQoYPn$x2zqrbBnDk(rcN+*1WBU4eRC zn5lcT(c7UG*yiftK&EQiSqJM94%M8x=mwjN#{qn;%`zCEgUQFHd{8%}(MNm>=Ejdf zjz>V|CDC`mFq*BxYHXV)Jqwnv&#`=cPO6VPdRHIW`vMK>@6e$3G(lLfN>$-PE=C$b z)x^S7!YlSLt;b7Lh-`0BL|Nkztt6^MK(T0p^)Z>yFA0y$lzu>Rk%oc|s8_K(?6)`v ziYvux7<3T*q_FU^DA^T?@*&ueVNJF^5NiWo#P#MLCMDUsKV<(vadMsJ6W?f=;)h6s ztiO&cO^z+M^kOQNw#I@jSOIY$$F6Et`@L zfCAfq*!6in8YibSPy(@$=pEhR)qhZ5;!5qZt9@=wVCWr zMor*#!S35@O#jW48!RMN$yP`FxUn6rHEQI>dt9qDK4y=pEyHe)IDNphFDRD{=q;(X zrM9Y}EA$Nbby{E7Ur?e)t*f%X$MHlMBYBpunJ#u4Sb1#0^O&v>YB<%6P|XEL1xx#7 z-@>XspiOgIu+RV3rp%u+bIz3uB6Ful=Fk0FWa_ke)8^nTfb`613(m!yR0J|dkOJlYDR$C|So3$-iD89?;9{PLOmWxY7we9QVYd3eDlQ1~0R4HWc*FdVx;pjKn>0 z)p!T+q`^hc#DAl~YjC9#{1V)g4%-_#!8un&N;2t)7MMuPrBKb@_QpEYW50t!Tw`$29|_fIaCr`1 z3)Sp)5OJLA@EDw!E=+)X=ecp-&>~6oN^^B-xtu3 z9hUFP)*YtrxDJKw`^<`A&X)r=?{jJLPJ{QaR8&kF8TPpg;yFm{3#E9xM`>Pn(;=A|56K=`u1cCm-_a63okQtQhD%;EnN7V zng{=~g$qB|=fQ8wga6RNCEkZET=;+7!X@8dv2c;Y?=4*Nw~)ex6FCe0Xdb-M!i7$~ zg+~-sd`()or0Y@(7d^S$!X;hPEWE_fpKIX~@1i{T^?C67EL`H2dgM2`6c+;Jovu_@L+xQTmX-NqR@FGfRi7S9A}{U zppao)-T=KWl!bLx07A|rgVd3I`l7&mWS6H~vSsTEE^8ZBuXIe%7pSEz3 z&ubPg>H33(M?s5jkA;go`<{3~ zL&?WT5gy{Lp$pEYJ-zLWhwgO z2k=t^_zeL(1YG2NhlLBD&*#DSS-8mOV+$8KglTXMCvuQ{|7;%o6bqMhRa$sNQFWYj z9(<;SOT1sRaLR(N-NJ?cP7AMBz8&X>7A|tzWZ@;o{|*Zm`M+l2LO*NaLVu5i3!fk7 z!H+A}42b;83_qt?c)7tZuyEmLoP|rgU$AhI=VcaNZs@NzIMs!I1;5$CUE}{YgOmTy z<6rdQhXI^)gr5fkc(7gjD1g(y(CMotl5_egcv&8NcmNOfGcOF_q%Zk(v4sntU$St~ zhv^nB`ZL?Yh0ZrDJcYRF+AX|X!^XTdmtOIIo8@2V-*4eUXS;*`16 zXbTtmCmY<(-?9Ks+QMgrg$td!Jotqc9x?n}kq4h);S%rHEnMglP~PWcP{Bg2}YU7rlHaM6boEnMU? z)WWL`pCc?>%Hy;=_*x5(7&k3m3WFZQ=DM zUB9w$DR;lI@R0HUI|~;&dn{ba#a|6BjJ(Y514+VqO4eyb=7<`4%qxzhlwYzCq8zh0nu{ zKqOsKUXHbJ;d8LTZ9Y#9;6XmmwQ$!k)MVkJZ&NK?($!|+5ku!j3okSHy%sKXw&cNi zm?NFktK$D%3y&yYj&q{1?-2izU-F*QOME9zua&*x?7w%dY|ZeR>QB3W#vrM55NW-N zSk}rmdR_4^GMVeTaM*``SzysBjzDN#kkm_(n2HUcz*KC(6)ThQ3tL;& z%kK(Z!zXP5Slbv$rZ+ZpxsMZbmYl+Um{ZvK7iP=aG_f&V+7BxUa1vIr34^_p8)X4& zrfMrljFpF~zs@&QHj>u8N`Pgaq9Br^2 z?$ifHYr()IT&W$*o%inzUw#Z00~|wcUq>uR3{!xhIMOuS@fIL$rl_}j&au~)&(E(+DNj=j#@R#mKu{!2g%=_Z^V}H@B5V&$Dg|#ueur_8!U~PPYibsWoYcktyh4E zM6jR;($Pw7)=6NM?W%+~_!qKx_B_ba+4mX_(lg6uvwwm~ueW{QtJht04c&zlt_ue1%hW)-Jhou}3Us{}XTP!E)~^xy}$+^hVf z+?w2RnWo>6+L??QFPl%N9-ZF0*$`74iS~v&Rx5LC6|43T=SisQx$T@>e2wXyh;K}~ z_}W}d4Vk7VDU6}4tE!(#n$^Eg3h~y@8F4@zUI#Nqyy=bc+ET0|oQqjsgfM+@1ZnI*LOS$vpb3!9Kvg4Psn3VFR~~~)g9bK5$78|nc(q`6JXaLpA+TWgvnZlO z6%k?0nB%8k#GA`^sWl!iX-2UreTR?D_Ir|3;$i`GJSI!6TEjVQ&RzkJJP^UIp_ugpq-g|^uWrU7R!Iw&O6;Q8nYt&*0#ymeQb6up z8qI%f?cZCXi?u|R?B}0>Y*NBR{k#*tOSDkC&C-h4_VAkBP_OJW_+jDW>NTF{Nv>Z& zd}FcRCRwPKdh69uEa^M&0%rO>rtl2~AF|OcLS4$GGO#blGBujZ=dAx-9{n;Y8X+`@ z3DJiK1+DtE+;9XkOyqG8E&OPcevM~Gs>)DRL}XO+@Gkj;fgGf)Hx=mNi8NGVdU(K1 znT}aj^Yk!-r3c^TE2bjCPDoKty0JpxgBl*?$i=vFIt?t_v zOR|R6T^VUWQmAiC4UdD|uJK~B22J;I;`?5}sbsz{^=#W0MWM|iN90NglPmp(RA!R@ z5tchIrMe7~VkU(MB~eywrEs8l5sM$|dndb5ty9q=HtW-bGy}g5KVveB{g2So`4-Fd zptrvFkF7!Y^lJ}R@naYcd$V_PFZVTti2;!jYURO-zN-(*U|08=_I{%W+{W%F-T$sV z&~h-p_2w#al$T0xHDP_-MlWi~QSiC6HefZ1sTNAWqzpm zXPB{;op>K~cKpG2!F&4qXRJLS+q8X`bjp?U^~6OV1?RjWanT3Sr6C5FF%-ddc{_NG zLCpA%;z}p}*`p%;GKJ>wxWQ#?PW&efUTOJnFu3TG_#bQV8q5Es2CuX5%M4y`;c0`r z7CzhHNegc=c*?>T8+^Ql^YNdtmSDN!*0J({0Gtr=K@cfmCS(yn|Pxad@n z#`p5zKgoly%Y*al;!yOr<)6r2Y+(b;$+4?aE*ewl?!`M%P^MQ6ATTQFYX z-?#9H_U7Db;jY1dYT;5}{>s9I{*wWmnB>cW0M2|7I?{-Ve1uM40&s%Y=||@T3l~1m zw(zL&KOzs#1Ka3$AwNRrA`6e;9o?lCE^_{|g-d9jhqlpJf5OM+SK11?YSZ z&my;P2Jn*u_;&(0`4_p}Vc`+Hqtk;qx%5U9>NtO}{FfU1!#sFD(`n#q##?Xv53q2d zbGC(xoX1*t)X=#s51zJgp~F!pI^idxp0EJj!s`uwn}uUD1?BFvaH(h3Svb>7x7Wfe zHS8R)@SgVH1Qb4{T|LUerCmMU!ll1ZlLtTF!iE3w7B2DHYa)dID+B&Hcp!TCwE)gr zp|dm(zS6>l{#pwcK7VH6#YUbRE!;dhTl3&gS-8maSqm3={w@#xaUT3|HPDvRH{o-z zg-gDlY~hmLvOM^33zs_LJPVidKH9=1-b?b}SLVSxEWF;xpIa8viQY!kljD5X!b=VQ z3kw(hx!=N#c%4lFJg9H41#tQm|8H5i(En>5{4;9KFUP<5j|OncQt;CQIOB}qpKg?e zOM06uyk7an%!h?X4L--hrCn>aaPfb$!P$7b2k=wi zSLEm-0Kn!s`v8qYX|uP-epaaRHq13jHbzXBfKkEZo(wGsWP-kAa=} z7B2Mv)xyoAv&O=chR_BJuQ&MP2Dj7oL;w$_>kk$#{O_^wh@tKZ9aX68i#9L(H!skGPi(Z-Ra7GxM7s^uTj}Oo}6}ZTAQUIrai8pQG67MX7OS}l8 zT*O@Y*}yc2n>&AMx@DGFqU6qU89Fr2zU^mM#?JYaXSvjzA+b45y}A`!l=v4KybqKi z$|cFG|GWsy`75JfFX=s~H;%&D>uO&kZ?)PjD&^^kr4*hq9E6!CY@ms2`+k^f;FxpV za$~6%)GK}PJong)fMm<@m^$xxTfJEwBW}F=Qga7?ZAmn)y@FWhPU&|}v+XI}!8KnH(5-m~J>!L-t zCP8TfE{#A$Ra9;{@O!8ZeY7&$%6~m^DdGV5YpOv@XKjQ;+#j+=tZ* z%$49J?j4i7`msg03mAh`ebBW$S`Lg3w{_+=em`#jl;O(TMC~!uBq!WC8e_?EZx7DF zzDZfpbh)}Ogbl*_buTH3cZF0XXpU?5n+|j0u^meek9#{HHPTP`#Ubp1=N7D1F}r{n z3u17+9j!ldAqR3qWnkh*XX=_0v2&M{Qk$tVT?q#>!rj>l{D>MEe!*Zbu91Ajbv(AK zZNBE$$Hti01U%$simSYR-h1)xt!`|4TdX0y3;Rd+NpUm8hD=>4c7#r)UmTOJzB%5F zEv>!hT>pYZVGUr0!47_(w7%x;Lj>{6n1a~OxVO#Q(s~ONjcI{CF$u1p2vL`qtq+59 z%+ikz8KLqKq1z7>v|jKCzv9+XE9evR@7{h+bdT~=Lq5VL>4zr@$9y!ZF!i~Q65in; z%@`0g)7r<|j6Ku3aQwU$Vcgs0?Fg^A2h?DDAu*eL@~cBIUg{Sw*pnzkmboZ9%njFH ze3&yLQ+mFe`4?>1kDb}H_+9VC@anM`-p6i+nQweDHj{dYXOeSA<^2*C_A(D(|Kt%~ z_01;5@!EpS*FW(#E_sGJ%+xfbx5c}+F*(>k78&e%+>YN1^_P4PcV2>wq#$jbldKDO zUQhY3G${Efy-WCYAsq6K{cHyh*ZKGa40hVaNvchLHfBPl*j(?}Oe^-X-HBr$u5C=8 zG@?7j6WGJabV~+;D7`1)4@wjs=Y0ZS%w1Ay-C^f$c+EG!Xzv`>JSVDN4wjwRu0X+2 ziD;WywH4)sGGV>e2*WANZDVWA#tc&dm82r?X1*2H)T|JENJVX05Dd^rB?)(zzqU5k?P!e?g zen?Ucsleg3+T2nXD{=4o6QpSI4T)0@I#Eo-=qgpOk~3W*pg{$Rj_!p=lVN5{W^94C z-7AJ+V6Q^GRkD1YiZqzzWgy1bKwohg?&QF!3qg=2RJ>#u$uJqC>ICrnK7ydB*@FvJ z;vkm79h?u-HC1T{+iRk9{TYaxsT=CO=j}!1v*g0Y^fn%E0n33SxlLqo!h=EAfidaO z18n1&9vC>T?AX;$NG#Li)*cfNkA2jQX{$Sv$|Xh2A0{-A z_o$){LrIeSXN9jQARFit;-;XGW{QozC`Hyw6e_iXEuKE;4i=RC+g}fbJG#*^#T#k` zwpL!l@g3F|^cino&rVZ8c)3@^@aq)X@IYkh%moXkrCZo>89Qx3%e1KtkMwkKyoZwr zlk#p={SR+n%6phSkFFII?991yWVg>-bQU*;Oyq2}s1n$!K0X9H-+ma+lrDRop$fpOR zlR*Lv3%lrP!Hpb@i4QMb&_)VX2hV1R$l!!ew(!)J7oYArd!X}RYod<#u8Sap+sT71ln?BHX}4NyEkFGXN`C}7C+h19iX6+4QY%K1xcn4 zP!*X3*Pn#8)$cQ8OTiAD65vf*f!&LBN5W8s@gy`U_MvO4BG=p2dT)->Q!MeCQYwQa z6|Yu?uHa01nvLl`$@Yz*(O&V&gnxW8t)-Dd&COPVlo&ke6-QGUt$oRiZb;%o{+7(> zf`ua^D0Su-x&!xzaLCX-Fo#;!(Eeyh?S!j(_QGg;xr5`OL7;1_qe}|<+y!+VM`G|R=DpKJI$(uX6`h#gS0^=3doT? zclL_MtL`)&Sc|dnP&oTZ1fAz*#!{nR-lF>aq`U_&VSBlrJ;ih%r*inrCAfxhk;*bfu>+q)RB;t~%~B zPA*vcpbIv_cOP<4_mz-K#o0|>al2}_Mij($#Jx@4#@45#AmY=Hxr{Ru+}hh!U%>Tl zSBmR;Z-hHv{tK*B*C{XUn_*q4C78l_E?||!$7ae`HKr#xI0orkakLw?x! zdl3c8#NhVDJ&}+_hE{cm>nBUy!ej}G2+FbRHA*i4l5$#ys!gWQk;fMc4cNzKnoe*= z`c0>N6fe9OX3zWM-chEOP|4ZY`ZQI%2-Mw7=mMoFy!SRGGwY0otyW(l`*y_(k4|_f z5xQ3z-}ki9SM((LA-M(dO9{u`;i>dC=sU{q4uxN*)RrIY>+x*9e$CfwrgR09I2kEG zhieVLVmHte>jdUMvW0CCiQPeBh)jLGimoFw2dVek@RMJ$MSKQLYB;}MZzDZi*Q%@j zdZjuqqIOT_N9qju5a3BfU~`r7IZH2EVZmVDu@r$tpF*IfkTqSRP%_NtDE8jQX&NW7 z-QL1rC@SOG6~5hk^;#dand)}v+auDlSFGHPruzmJh3$b$j13)IHjy7^DuH+SKcGa|F6&2D%I&Hvn%$h0}hhvv@zdSv?C z`H|!UEi+pRph|c(*c-;$16d;4-CU=G^JHpM`sj zh9J4rQB}5?*m=rlD5^eP7hren^_40@SyxiF>05dl z2xguh+kodm$}_fCS65S=BCDF2RY^8Ss)7eOs!C1+@uh%goMP}DMyXUrXK)h+LZEt3 zniR({VCKw0k9uY)Mm}H@%OQMq>+7xWZ=lsV=VVp@$C;INI=%5AvkxEE^%yjq0|^2&kX@gkDVjO)hj zWZdyBs{uNEBaVBod&`gq6)EJ*RQ%8KM}*?Bk5J282QL7|w~b;Y$w(X1zoujz+_DZJ zXZ$D`?Ux?m)}o-}yH!~Ty5UAV#r+yILZHQiqsF)1@A_z!6CH1dSKR@FI-Op;4R>w< z9i@vwx@iQ9KHNj2_0>Rt8%+RVgc;D7euav+N4>%*Cm=Qf91kl|banRv9I-091Kz+b z4fT)|eas9xqJ#L%%w^I>cDW}o26!|#@S#HBsmFj zI64{PPLUX{Nzw>sK3~MX-_&R-(eeB6nxB;L2~{xiV=3O#VQ>n)K70=29V-zg3k@Ak zivf&75!WH3m%<;8SA>s_4J|L>%l`Q)2EsB7wYb7%txm0@zl6697Wuovnf^)ucPdWe ze!_`ujC+rTGkf7Dp80Y&PFM`D*?@=G#&Cw3$B_ci*5?0l?=5Cd8E7=7_h227w|9ge zy0_{B^hgF!yo2xtU2?yAg`4>*)^6xbAdM&D;h%p17M{SFjUN%1bv;*~oW2?NleS3SL^n2)vV@8GOQ#CX8S|Z+UtSSa0p` z#@-08Zl>%_V~%cR_v086Lf;bI_iLA6^x_TIdp*4RD0)g?r%17bMLLXDDU$a*8<%>X zo#*2V7{h1ha3OeBUmNHWoKzW*rIoC%N9S$c+M&Omu_Dx2g|K6eSuS;u%<&d z{VpoXN&e#KBpi;^Ki<8a&&}S4g@<=3g zzl3KxRd%D=b_=dktj71fluDzKcRh41%_s)S=qNAxlUR9WcscjzLh>ddhAzg@dJEKf z1}Rc?Cvj0L4~#(auTxbBBuWX87L~#svW+>yvc|zJ3q8D(2C~aRzj{GV+&`CJVXYj2TLqL=9%~s2 zsW~3|INZ4kP(%7zDG_9cii{KOu9ZCE*c?VE3pr4YkJr`()M*M4Qtroqr0k!IL$UhC zGqYmd5L#l$j@Y|xW0Kx;sq|~4Lr$^Y?dGJnEg2XztJQ(Ss~d_a4SdDw?nrl6+zZ{{ zAA@t{y0^uiZ@n+x{kU6;j0mscL8>YVlrToZpA2_C2I7tB-!N~fQ;Djrqx|U24XBGV zb!vRB!P}05HZA~%H6t_C$0w>V;`W-G8HI28S8+T?TTFdVq@VZ8uVvk*#rmWlx&~Fq zF&KZ27i`2qPG_uEDfP(X15)vt_g;6GS63F#EGi&R zDtj}fWv=&|!qdB-gkZ4r5Z^E9cTs|HaFs3r4e1R&&cj1-#W?IcIz}(_lSIKLjGefJ zeIODXH-tF5axs>w7?H}7_6snc^Gl3JkQ`MD-)ZKhi;@~EYAtlVBCPbqsAWU?=~O1v z?he6v&K+?d=fkX4H7S(N$JnqE0eO!5L*iZ;=q+WkGNTIO-VoOdo%`*552~im&0Jj2 zn0{$YCiHFBXGIfU!#zS9(#S@07!|aMH35p(TE8gn71v7Z=z5V+Ug@uL*;v+4RL>Cmwl*PucQRU^?gUSnZEgpNa?evE9$5aujKg!4hEE~v04CZ5{?a>$`k`%Q* zC#9D4QNq8>anHb{SKRx!7DX@INdZ5Ee1hUWPF_h6T8ncipFyd?P{Q>9D7b;Bmsp}u zHO*vBDVcaB91)?c5?I^^-Ycp1L!NUBiwB}uj86>NnTWlY2#?#20_%pyJ{c=6!6Bt6 z>uwC~AG|DLDo6{XTU%YP7z>j3six73-a}QB;&vH|8yDx-$GyKX1(Vo9FQ%3;1#aQ( zCdafAbIK^0Nqq*|@N&YN%F(am77k+iD0j?-DPv4rF=>X-s2XQLaxKR*2{!@pY9Or{ zLl#G;a*Q*lh z(ZKa%&eI3hxS^b>c{;ziuw(0@ll0p=4|+T6FsI|~ufIXoHR=7X_c$t$`w-xpDnB+X z8tuK)kbZ36tK^ZMl9|CBh!96`4L&LE9})M?M*f}Xm+X77W7opIXhYEKQY(~SEZp^R z=vc?ruWyh74YHVhSua&MDsSCA46ivJxzLm7Hk1t=ArlOG4&r79oN_|zd4oSZj%k~H zFXFUCj6uJbN^c(JO~v_U!$B@lds^!T>{T#}<%=SZdxN8x2wjicz(go{VDAcDE3}8H zahcFB;(n1n#mV#r(mO|c(HqDLi#XFjK2XSy>C#&|CA>&BgT<2cqFK~EHtb^1_rgr* zI#X#Z-->TiReqkP3{844NIxdyVmiu?pgY)w7|^X-ek;7P5HQBZ^kZW(AuVw4QNOwX z8NPfoUQn}@h#?ZCq<(Q9-BeZg^H0w#DM)0RD!Sd+^KGZ4(p`vel?tSF6vqy>cXy#G z{H8zDE%=~&du(6pi=@aX5ufTVxZWR3p>Mf}rzW%T#`nGAV#2wUA7-rO7;|I#^{NjL z==-?G*T-)$-sQ%s`-PXUz;pNZmSK_>=oScm6H-|CD88u3kO+3PAH9_w;*Jn>Ap2b| zp>BzmGWQs(nxpkg5u?k-eu#Yu1H;-|9Q+#%sT2H|9fp@tW}P!5&6Lg#1S#3)4Uy>Q1!Tv@3t1wne# zGR1-H(POZU#rFdbA%c04ivU4>#j)O2P?d!heetpp+KY}XyxUu2K^fHZa2jWr4j zNGctwL@&2J`&WKLgE;dYJ**aV1UdbnwDBgg>(_-7etCcI9dsr9ljB3)j4_58%- zKtW}y&?erf0v98)>F20x6l(Wov@_SD>TvziZ*usl25k%0mV;R)?lyQ~ z`%RuX79ATDUb9@i5TB|PDB6-N5yy-uJQGJbV7b^28pzc~@hnK3Je zp3b$%b$%Bd$K)`iH{6e5Iu8L`pTx{TbW&W6u0BF~n7YO>(rvRz5dAIe4FkpZxzHKi ztc%f6VS>q$I#czxeHt+^8TTu_YRn84!D|UV9lJNiGxI*dei4H*r7@m^+l?ckcO`F% zz2}!+>y@^*?jD^<6?Mlmi)&D)yw-XXX;OHq-S?jGOW1>LJB9I60({k&-sqS5Y-TrN z8nWFVpuQc@9RvGREc!_zd?eu=!5kihZ^uXCevA!qjpSqC8wJ@to;3kl5A^|{D=Y>t?R#KBFl*iA^_kyBXY1MVDh%xDh|l zh#64HS=m=H^uvViXMD)WKuJ6rC2^o`Xl~cd1{<2tb*e;4MXanWiocUR8`Vp$L>lX$ zba4qvx^t?rlKlS)6%Ppy%DHFoH!F3jGkT9kFBu|swgugH$UL4L@@ zrC<(KNymDOMyX9Db^}o5nR+MV7yh}~(eS{&3A@SnV|dqHKaJ(^$x1sstrATgiP@qyr}9ZQ>t ze^^aY>vMM5 zaqx<lYcL&q-FR3kz)<2hB$Hg7l$52PpFVziohA|!?zsehHpK#|a z(@v42#`JDsinZ@}w0b{NUH%wsR9e<$>)|)oFKb|gI-lPctxj(IBZkQ=hmGe#yQ1r+;556Wi=#}Tqyal|8r-C@%iIrIF8 zJ9EL5D`ribiqZEu3#LW5-f+RWkyC4MvSZ@ni^pAziGgvE@eN-X*A$6=A>NRRk4PmV z&Ud~|_ud5%G~AvGO7#txELc=h+^=XYn4+u0|6p~ef8I4~ow3&f&Usu@$PE|FUJLO7 zH8|g~P@nXe32FZfKPeD?#%J_{+N)vAfI%ZvXl~N5rf~FtO3+~VF$4CP`2TmWhJf&J zTW=nlha4IgG~Zqgi?}EoZmE&)k+|n=5ka^?`l9xbBu=A^pu5S6SKgWImPfTeHfjE& z;mIcBxA$6*_)qPLN#6+nCRs{OhYJ6Y;h*veIteG&e0w##V8WLK1LI!em+KT@q@_Ao z0l&LVcs9I2C*cHRnXzTccl(V%Dvd|xAHzy`$-k?BsSdaCCzqwC%U$oQq+8H@do@V- zYVl~Uc6bgI*m+N{>rDL1O*pyO;SVJ{`rTilLvYTH4kOn+`&IB+(%&EVhl;<*=s)EX zbawo~cfou5`|sSVfpPsa*8b}y1qW-4-WucJ^941ZT!GNru^kDn{g?KF6HIoQVaU_+ z;LN5&`9B{x>F+V^khCYsJpL!-!7s~$PtSupbM+#MG*|4O&7W#6)7L2PX3v{Hr-e6H zPMb4(`dp_m(bRCsm&T$s9_tdGGJEEnsaNJad}+?q;1Pi{<}H}t;>=svvH%Rgy{Ip$ z{-BPd!>e4q(R*H)H-i5g6&{Xw(EmNf3RXDfDgNJN#Q{hEEUSXo^8t=H_o)$la{v$0 zKarl`?07FQ`9r-rO!?414F;!w-U|IM1n?mJWdWSJCH_a4^JYnhaR`2W0H<~e-uihw zz|n7Cb*F#Y4Nf}jnu!01etl3KKH0)W59eKxzH)YMiA|)csxnqRtU5MySe`XDl~red z+BG)oDH!AG)wLcvQ0&An#g2*_xX$Jiv(Bdd&&~cLYvCoZ+a$Zh`w5|6TZU?kU;0U! zE7VH|SUTjiTo|8xc;K67Uj6MGzjB^;9^=Yw^q2I85l}`gW&ptq3v>~8`~(c?Fs{J? z-YxWqhftCZen`)b;Mn3VbF$eNj>PmNxd3v(1QMLUkrziT><=mi76p&pnpDCXs+2CzGxqat4suNQ5hL41NwQOpT|SV z4NJj#Qs?{hc=)U@EDGpRc*S1SHSn(EFq%w&PaxFi6N*2~Gsi9blhvRo(YM9gdEaNOuDym29m6l?R zfa6BW1gwa;c^eWbqfacUuperIVG;b)t3jm{W&xCnrZ_-h!m8PF9TNU%dsJjbp!6_S z$}81@T)#17b{2GN8*ADcA(B%Oqij-&p{()9%=a-@-H;BgqiVxPUBBt!3Hz91UtP4| zNaRIHs2_d@Vl__pCcOo3?Sz`v2Ot{ON|O0KD%@7L)|BqX^bUN^k4qO{X9|y$A*F`8N~&F0gKa*`c0%Vb*O~$4S2t~= zdm?=S3jzwT+w?7(B~~G*LB?i^k7iOxtm-&}b=kQnz62r@_M{ z12c>j3z$@_NZk=!$c8c1o~ng*V9ai>TxSDvAyB&X=BUh$nBJEYQ@`Dtv03Wso+N^? zlBth7dq+V;kFv0986l}!NL`YTxN0ewJuNAlKlA5({7iV0KYu~;CeB%e9a7KwYk0-O z_~Jmm!Gh&!gw$PHc{k5|K}qI<)WUd1asmta@ygDXvl zrQ`ypjr)BzE2Y8BKy?#d^F?%}5b`iZ$qiqmZ^9R8e<-PA7eUEiM~I1!Ar=LrX84dK zl;7NzyAW4E9)VjCO?g|5t2fhaNFTsdB6gvEP{dF>p`2-pVjtv*zduOXxA+T7dNRGO zwnu@v4(7sK8>mVRG`IM9rgtmTtEC5K)lKW;z)DUqiPb7$YDnaJ+3!#(UGxNhc7Z_i zZ#!6KH3eX=;K3-7-lW=8soXmVB2-j+D$RBukwBkwO58w|FzIK((5?9`sx`*~GROnF zp)NP_fQgdQ2hc5NQ#G)>w)IhoglSM&&w`{Ya?OzRXP7xd>FZ3BQnYD!(s_!U)VYXV zfYnX7{ZiHb>QaqJR3h0RgjW{B4pXA-N!!W~Fh|8MjcG)V#v2ue@pJgFOZ9;l3=T9W zRq&&DUVw!G@ZymE0t~F0)*qU7I3OkL1+a(G=7{kw_2KF-Db_7W?UKs2ai%grSL$`p zQ5N&+s*M^_=?_#Tu}xw87gkcYu+#%vZBMEzRKI-y4Xo?e3d5r%sQZ;9T(nN? zaVai1u)G0;$s+R#Q!L6L{;{9ZZrAy91G!CJ6dwy=qW|r z_Idl%H9OnPTB{5~%*VX7947}LnI|xeTYFhexN{h?cCATj`or#x4e8Pcb;2+cQ^<6o zB*7Ab%2a%G>$BMq0g)RHJSWn0aq^O{pXZ#q;M7>f z+0%Mo9KvVMn%W!f{iNd?Id{&N7hXA~Wm@FQ`BSFOoHnN=q8zC&QVFNOPro1WM)S>$ zG44?ZkCD3r))w?0BmbWtxG=2V* z+0&egIdfa4Rg4}x;midsQ_@#C73sONXG2(8i2sG(2*R>f41SN3Ts?o_M2`9?hs$%m zF>cvBZfS}3$?Avk6q$g7%$1-1#O-my5Ca^-u^0tiIUY#U4qs%#-xTz0{01S8aWQ@~ zq}%gK!jJAj^bP&e$+h0x+u_HX`0enLehHs%jQb`N-iVJ;DktIPIt3_cp(5<%?l9q- zd!ae`3!HC^d+BM~hvXBudX;$JQi znX4WDp=3v|i_DnX9Y(Q8?sNFJ)1PmQJ7UJbULmo7v*QoE>UB$h|D9vpEi*Luf;2eguLq7#x5)5qaf0YN{ zm+|h%}X=nbl>2tVA@tpayu}SeFG}G9p7?&38QT%m2RrAt<9f}vx%Q@Jn zSZ`8%#Z@p4sE9dJ)U~S8x#Frh3qhmGnKhJ~70;fsX#OJZSInEQS5#FyE!au`J0TB4 z5N=m|1%8J+i}-qaMHO~EX1G}I-HYd?F$AurIu>3zd*Li|H@#)Pxw`^)3+7?xrIzVL z^n?kL?64fuu^pjqiJna%2q*Y*{peh2u7b;cr1LF&mU+I%!cF(gdDOxOo9C?-F6IB( zJopEB@Gr6=g(IIQ<6q_$rUr1PSLiRugRiu3X_t0cxbXi{9{hI}F7du+;XyM3zu}wu<+%E{#Pwr{I^-S!0JosaI z@ZVUt(Emdo{A~+|b+>jFE_4o4AKtlgBzzuY;dMG$&Pf)&*x>g5w?Zdo`4{|R3l};w zEL`}!#=?c4;6Ah`gBQv7$1MN#hR^L5F8sWh2j86sFEAg5QodY6|L{C`X#fxE8`n3{ z2^~pqa6emSozQO%_z%_tlLI*YvwuZ*rG=Mi*qLwP26h%(xX9<)Jor!Z;Oi`0+J$E< zT=;x958lsonM6M2hS6{y{A3HKEa=Y2gU2jf_!(j0LT8MH3qMox;Bzco=q$2up~Fp# z=p?<(`q9Z)_+*3MXyKAy-^+uq%Y$#T@TrFWt~~f}EL`Hv=D`o-!H+T>UrFyI6Ypp9 z;9Sy8XZt_P!iE1P3m5uREL{B0wD2Y!owGO(zTCoB8~@i@xX9;wdGN>b;BQ#C@bjjH zOS%qNxbRcL4_i2qo22(d3!kOEIj32;=x3#chm8O8Exg#^qbywbY_@RWXR?J4HgvvW z;iU$@)xx6&-)P}N=Vc3*eEDM@{74$*z=_<%|G9ba(RuJ0dGPH_Ce{sXW>IM z?A#H+DYr6%|1^M;4#!*Rer0f5K92gCgXn>6HndOj6>+U)WHH3579)aIs->&Ss;gbs3Gb zl<^%*8X^?_BVY?|4{c6LiZC4t%az{NcbJ%kiBR+Ty{zxT7ga!}6=3V42zld=w!XuB zshS@>$o$TjL1OoSk_yA9ds*X^Yr;y^z>W~6 zHQwg`#2Syg<2(n#s;0E9@eV_MmNVk$F~HE)c-U0nP}X=U)P1(S+NHvjw!1@`w=-Y1 zApMx^R&!9;$Aq?cE#Gx)W4wvQ)f9N~a7?V9O_4Qpg(`V%y*qh7uguKkdbw*5?2)84 zVM=P93>f^R^ov8<3>Kj018!NF@~T8CHiWb^VlGc#6kfI&$?Ro6bC$8oz}i#TVO*GA z+=0y*RMNDu3=9^KZRHm*E#-BsJ1JLfS7?@1()u-L8#om^lJ(dX(uxrFgfM!Qt@pT2 z73+>mdQ1dUYTcrFuWS^RwVQ0r1#*WlMub^jkJ(bV^N;u_L6Q~E+760#iZm?z5L=)& zq_JCovMfZo2^ByN6ZTUWt&0{EvnUlS+rr{d(6sPA*sj2E>C#=aI#3!Wb}}_>=k-`g zVci_8q>%GL<3dmzybp9I4t}3yRFxo7Q8&ugNM#MOWDB`~P3p2^!N2QIfEkI3iuP)4 zb42q@?tp~0I-+si2Y9+%6&4;)pNSVVq?;acjJjxJLu{s_j18lu@H=q`e|D3rcknYw zSygQBPR8XDkNNoi=7NEOgBlpqJOGmj^szW6}{3N~nIE_X09-;ZRWv1^XuivP=1w!-{uVstQ#(4r@S zo#PIbW55q-(ivXEg~Y7BSPWQ+(6*mE7hTXBI$h7hmt_I*`>g%#x9) z;&U4^#dXlt{-E2x_3_?CF`!*iYRcQ{O#RY;t@5~G9*%G@wLeVo%4r8YSSiNKVA-zB z9)s;0R&gu#X#3Vy)649QRgzK{WAhe$hI#mV64E&ZA*h>HYMn0Gyio!PSdV@JeZFWr zf1U+_=8t<@kHWCEN0f>aV?8<@IS7%c2&kg$Ly74df}DnT$~)*P8()*dy5d0pLp_Jv z`)V>O9SCwB^9OG~46j^*IYF{}n1W#Rscyn6rx6dA94j;|<4vsDH@y$E6#Y>p7~4$C zd{cM+z+6cs2q{fF*nD$gv9yAfZ5QQiU~ys%cw(ZdPVDXM!L>2{TV)H|^nIyyX^)6{ zq!Qeg9}TT3M^!hed>|!Ker)Sqmc=F0K_S977Ln-Ut+sK&gG#!w8#D%&K|@Q`vw0Xi zIEOZ}Jhb89`7nay;&l}%1aZt;t9s&{1R?V?LEe={v)rO4Xgr&}6aY%8$ym*BW9Ei> ze18ecDew6ppZAf)0JEH=;?9O;s#u~bP*<@ArZFw!|8$0wDh|Y7!n{2~+inJ;1`>88(XUXwWZ8S z@lbaWfKd0mwv-}A30p5W=9I1aU9%3!KlEQo`4XM{{Kw=;T^&?uQZ#I9YQ!A%O8#;+OFGY$;3h0_ub8 zh9taPr+_ADq5kXTA|`xuFEkgwz>{!e%areCoS}V4J~96or^GAxRlv;jkq%&f7n%5b zfq0N~3!cxGQo>h@M{~8qb9u3y_w;(FiGR5XCl@>Xp=3wDvOYIrghO@Y*rlC*PE8yt z{t_dgzuIJhRd*Wi*K^=N($WyARZ-UV$q zrTu#hcu6p@x!;}#e<2V4+dTN2d2rZpax&q+V8fZNf&ph5W|x)9XtPR;HnsI8j5f~} zqfJ_*DJqTy3s`Q_tz790@LZ|8xDi zhmP2Y@{^H{{!hcd%)x~NIQgu>Ki$cB@N+C&+PAAMT+-#`!LPG$iTBqQp3>|%Z&>)9 z1`jboa3Tl62U@uHg}FEjFE=lEI1!!Dxm`axLoK}6;O7SLQ-Fy)FALzoe4k_CGH2&o zxXA6=03M`&ZvZEK@vk?e$nhUFe7V1ohQWVn;nx{_lZ8uuZL#oMjQ{5XIAtmRUk%_)ukiCn z3m5<07B1;Mf`Q>g{(_&72VWMz%MecJ|0;mfEdALW*Tn%mSU+DDz{!u)`!g(D=r7EJugrtrX5qsBkMiL6 z2JoQV9tz;(Q~Fz77A|}~XW=4;S1nxl`J;s|)?#%2V&OvnZx$~8k2GB@yWAaZ;nJ?v zS@=2=ubT%S7r>+ND|*!&z$qW$XPSlA8Tzv=T;ly#3zz!s8VhF~L3h1{Yt(UmY~doe zCoEj_{I?b^{Jd-7;(xz|x0r~JFVZ(6f7jrrSh&dH91EB9jFwWy~WA0_wu{jIeo zJDcR5-v9ml&pGpfti6AGt>5~s-)p_s^1#Pw{Lg#fh7a$1;G=Z>kNbcRV22z(!yoDj ze}nsgU*LfoK40X4n|vpE;0AxQ2X6Sb+54|K7EfhM&K3#U~B} z-`NNJs0Ut7=HT~{2R=uEt$%pn2LGvCT!x?Fvw?r55BP;1c%@2imGl9Rdf*2CtUlm1 zeZW_E;1xRGm3_e1^#T8h2X5$p!UH$>&Du`G9~1utPyCps=WP$%;Bl|LqEO5)Fy z%i!7Nfg62zp%3^!`hZ`m3uy40^2R)H!=ITRxUt774X4<+*Tekgd*IqlS!Ru*iEqXd z>Rj=;cG3LI+C>(F_+^F&;VK>9z|9)bHVrrB8l@54;ew9<%+UWc7ks1({s$MFGBNRw zy5QtZ4FCB%?tvS5b$Q_W)iP%k7(TEK#NS{JFym+7!_})b!~-{Laff=~MjyWFf|H*G z8qX*VCx6_080Uh!`B0|ehR=rovt04X2csw7^TaoDsrJM-{KSoC@-yJmlbKbgHHBkS`eo^X79h;BE)o0&cP1>%JXxjkXx8oquPk$R>9aVU&vEhP zdUStz#VzL;cy(`UrT#)wBm00)ABBSZOQpI|I8Ba(xQBvz+4QR6W-Y zY>^OaSP({Aj`_IacB8-^3#=2^dw}6?8hL)#7j1dR7ioDP|BvE-8vow`>~9GFh7d5& za1?Q4xTyXpI1t0tT*oEEoy!v90v4eimoG?&8*C)R9aj?Ka4v)~-0)c-?^vD8chI$7 z@Zy#Pd0!J~<~z#XAmN>Xa)gnV_dvsgfe4>LcPYXs=p=9IB;LJ&DuEqiS#ZDVnm{S@ zX?Z^zWy1RgeKGZ&a`iBIzCh?`mCI|%v+;r(XZ{Nw<_B5@H`Y)H>|Lyq#A-W%;haW> z;6u64jq@7uP8uzSEom%)#6bOM<V667hZbr&%5R*eNgD_(+2gsT~2V>*=T(zjL15 z_WswiJ~;4c*V8Fqu`_iTZ&|NcX{AD!;tq~>W_A$TXt#aqJo0Z%fM*Pwbt4GHxsVUz z0jDgp5mIIa2u)d#tW>}dJ3_2Gf^LEwc_<`P$WSmtAIOH=<;>_`C^>T|R%FcOQZ6XI zB+A7_E@!Cw-xag4G-%uMv$66Hrilx^+Viivw@cEGv+bMXQLGSsuj)VHkx^IYriE@oT~HNGg9N^W^ee@~|AAuv{fKe*iysa*50^T+x*? z#1t2&Nrvpo7r53CF=lRT-`%Mjvv?;EF3Zq9G#i(#(X~r6Ih5@094GVIUc%BR;irqm6YH}dq5PT>(7w$^BZR9s1$7_G8zE=opLO_T zkx~C4kvOhn&wq*>CZWDFxZLci<#O!|r9fcL=>$GqpH2CbQ8)~E;^b^+m$SX`*RVxO zAB1_S=@#^li9I7;T%rXcBkOUm+Re()LdoyqcF@-vaVBA_I3?s)@F_)`-_G?(pE3WN z8kXaxC>9Tf4mBGkhJkko2DeNz4=Y)cH*rOt?}xe66y^eohcF4q0}mDFZbS);&erGS zhNxv^KI<2p>`V&ym|W`9al*;iY9H>z>v}p={A^PcN{_=N@h=wNM%9qA=tR@vv6Z-z zGtE5 zSL$3ZF8Pi59WB&Bzlt4sqI~I+cujr%gy_Tmx}`PsOKO)#oHruQ1EQ!-l2YE)LQ_!* zVA=Vh{*!TN?_=UisJP65EIfi(WB`37ozrd!Tg9tl0W=xXOb`@%D3VN1#SV)zTMZ!Z zz0V~cIOuE%)y-(E6pkZvdTN%B`T7|j`4mVxvjFi_Dh8(@swdikiL_6C{Dm5 zDdqi0%t67Aau7f0*e#(tqMPZq%DX=76YrZO{)WIthVicmD}WOAd>9biSB3kmvpS}y z@^K`$x{|7!J1B)veP>`DQ#AJw5R zz=#JaSLg**i?YNvqjIHk{>T&6OBUCR9z7b=Jj(CTz=#BINKA^2RaZDUg!ja?{tBpE z?kYJoM|?){v(BC-Ke>94iQ^}5KiJFK`miD9GiKU&1SZUqT8IL*BnMe1UBYJ4;3 z;aYSuxQe*JP)$2>!-g^_tt7iwglw1>%YudCE?C@5cOjWxN)h^n^UMzWUD9PvXT*6& zB%pV}6vTiMve4VmT-*yKr)JA_b+~$~F$nHFi9A6o?xe&+B#sRlk4Zss9)HT0jmjso z9v;m3fPS_5FwZ^D3v@I-s~L@ZJlBIeuJcpvhgu#4MwpH`c>AHBvFcpe9zyGuRh-@S zd%U{^v49yv5d2D6t>Zg5ydGgJh2uB{u5^zq+rsa{GO(kHn8;?id5|3OvrVNqsojBA z!&vHPv}W=TOpGZV29uz>ig}f=3QCZ65TS%{*7XW*h!4XS;yIUR#cH>XLV` zq%EIyr5+*BIbctFZri8X@M@}VyMrYU;(IW43nSoK-2K6ApW#x|5cI*#4A_a*N-~3m zHq4O1qCjMdzL}t#6XX!QzbX~(qNL6!Ui8KWlnUj;(cdh5X)J|B#^fwDC8KPH85us{ z&Vfo?z<4q?)DpQ9DEg5fFllScC}32&c)_W z60$znQgUn8itp2K_OoPYyP-YyAsQhcA$*4#n8P*l&o0MBnP}c34q$V0d{oLD?Cw;} z_(*)0?8-uPUq3{D3fr*|%_q@(1H?@nZ(L_I7^%bw0b_(rMr9%7KoiUP&hHcsG$TSI zWqXSxTBJEuFWz)0Sqd&HRiyHY0;ay(K=zK0I3)^4(tDppP=7m~FFyw1Td z%61g2LAyg*Hg?+v5a42Fa$+|xi%$fdPwlm7i9VB?v2@QNzMp$_4n$HpFA*2HmY);B zJ)Lua3=S2nd=>xqpmF;uQeE`|Tf{gwcdqPqX>4Q}*_Mf(j@xY)$Xfe6G#J2cwD#<_)jg|&P;yW=Q;;^~ z?6KE2v*2b61%*WkQY_RN^v86sU<=;ZR2|Q_9Xi2GxJEspah}uP*$u@qE=$!ZR8?jab&iUCB9&+X+)jRgDnq%5*jjQ{7-1!NG?S6UESVRUG%S>rok3d19%2T!@`BfZwER0QsMey-YaEIxmlf?MG?& z`h#-W_B4mPpz?56^s}MV^nU0hIG;3baM=c_Gjx|ZpO&E%Qrio~Y>m=W=@)5jqHt_T z?IzQDv_D}`j5|^_V7*%+SlSQm5hxROec=TP37Hwxj%pgXID}?^^jc7jRY)DC+t-vA zNM<8qBSPl{`QJ`Re0%D~emq_r3ijdD4z=nCA!xEJgrvY~d_tGqoz+dMgS4`%afFC~ zC{=a&AzB(AFrD*k>hgZYC!7x(|Kws`u2#FD2t`YQ^)1NfZu_gGy;C$XIk}dK#333wrGB#AYJk1^e#AkW(0}y}{=|Zs=)>rx z;7-Uz{>Z}%>;3Gc)I_(kzj6Vd(Nq+t>?Fl!t3FH2X`z;Ov{d2m@|vZzFRwu*XX;kt z%T0c=@1SVJA6;$6%R78;kk8U)baQa3n}g5VYwr^6G(BbGW#|c{&kSpQP>;pr;!u3> z2$r{5e8ge&FOc}qk;5C5&#-gRsszOJRKlqoc5&mM(kJid{=2eN{tjAgpd^~|UBaic zIX>|s&6iu};KSi~c$WlgMpkw9T--Z=D{SmM3oSUbD|H){iu4o<7{Q&xI{wb(J>ruL zGKOhrGIZ2w)(2E}WOmg%xF2W;Jj|J~_#Y|5VqAZLMm6?SBLaB&EOP!F|2ceuos)=h z8a0OoiJ=X+pt*bTe-FQ&MuuGqT)ED1mg5B7(m(K&C+84c$k)H~!^bS3ymC}S_8I4m zu-l%-NQPEY6jjv^$*Df}erb@#+Gq|mG_f`rKY9Ug7z4}C$O#8ApsveQmcvRS{U38x zmbgxY=K;($mFCxx-ParIO*I)y4O?IPh$K> zD$1uL@rsq;N##?fj&wTBK+oJ9+0QtLacS<4)F%W=My1<79W;*mr^d z0t!%AJ+kxvsITZ8us{&1w0~r@?TBe^<@+GdtXS4@kj@*5X8j2b4N=vXDLNJ_4|P#4 z?pYeMul`J`*CEjfsMhOH3Tj6l#&LB$9e)`*e?Z57Zn?zgnA~0cY;6XyBO0G{FkYhuj-m5HF*|Xj;8nH_XeRW4RB_zHGnClRnVKp&`|_0U zZ1$mP8OB8u@1L39pNae&K7E~kXvled!sb1^@^ApC9ALT5eijpZDDe)X8Dh8HOubib z9t{mvsNli9x_Q*@@>|l&v)fJ_$6eB(0T(qAj6>2HlREC!3_72qtwv)B7w>=~ zV%Q0uN4FO+FzP#l6!&XvPu~xG5XpJK2#+(Hcgze(e;YSVBxMu|9rm^Z&=5@sW8slx z>PHS<;XB9Hx+^ADc2^fYU)06wE@vg9qPnxYR*a%D6oN?ddOX5#a@eWCr0=v))~mtc zJBH&HmK|N&aSM9Tj(v{yTc~)O^DG)+e*kZolWu@&hEZ*$7DJ`TJg7NrYZSGQ%)@~W zh{ZII@RMrM=z4^lVl9}QDBlqM5|uvw95P@UgQ;h-_!_D0%|}Tr35(iKib&r7hY>j< zC--ju2urhKaa`4o9tR3=S+eprUwGtqaMFYB)gkMD3S$HjDV_f?Yg&O=nGTb6W~ehc z$oUX=O9v+=w)%cJCe@e)nAFVqm*{}JCaB9QI(}E-EHPVo44#>4{GdSD}>AQ1z6|G>U=2tFhq ztpZoj09hSmYs1zRF&Y7|qzzI#n}Jm5?*_4+P%8g)_RGmOC7sOJ1LoKueYTeT2uU)v zh|DMH5zw>=*-^W)<$J5lQE^Ozw2BHdK6>2j#c-f-HR5xavzh5ojWtMkXP{2tcLo;7 z`K&2lj`0i8_8sPg8!twne<3VT3nGfix61?D_z}IBvVcR7> zT5l5S^PrIbCV5w9%P>DGF6FvT;ClGhQ72AuetEZiUlVBNchKFe>DnlvnM17&)RE|Q z0#uX0WM+fBF922Ud=565%LTZ2-Cqyxh$jger96d6rW<81XpnM5oloQc5@dd!G z2sz%ffTI=|p2T@r@3Kd85oZ&XEooMDlaE zLv48P(QO3R>3~K)D2`ORg*}|nR)`WNJYtu4PS`J0*;r`CKdULZ}aT#F-!= zr(@E@#O*#iH3FN`Q9+;=*zKG4P8z-fgA~eDqW^|e7@sPO??$pI6D!+%EB2>9#Ln~( zc*9}hzS~%BB1hO6`L+H@)X`nRWPS@OmEg#dwJlwFjhB$o&{^nkm-&NP$stW+MVpRm~BR^d&f#i_xnifOk z2kf=)puUDzH2oFTO+j1jfTz2;;s?|f8U;#|%fa|n$h+mUeu;%GpPfilv&kajkhw_R zOhP%2lhSQ(a`+B^m){Y(D3cZ2mRyS7$`#rCGT{M zz-Gh5(3ad2&e{ZOLBn;A;c}26G=T8&YTI8$p@0FBH|;srKUN66!na1MUsyP$wyOP2a& z$`jU2d5j*7iBAehPrdJInSmF)DGR1psa2t5uFQY__%9jH0v-T7Sq)_g?c43OW$*F0 z6;(aRjjNeyPz-8HWzl#fU4Tf?`1HAQ(V)@~s6CqMlRJF35$~}hL_+$oGy=do2uxpq zMU|rFglp+>auKZqth)h(0us(`(juemwyCGSrysY5d8stU^V^Sm$@MA=o z4UR$)m$=pBg^~EPaNcX#s9=8wBPz+6xyhTd#o4Bhyas}voVFz4uUWigS#;|)3;c^} z7A;vCefWk^{-rhZY8OSHz~Ettf2@B*o|oL+4Pa(nH)_=~FJ0t5`tV>o}EbG$#?QVdf~@%=3& zx5HQcj6OEylkq83Y+vw9#JWf-b_$2oe4KUJNmU#K9Jm5{)~ASrvoR|_fGhh4YusJ< zI(Gt|#&p=X{)Tc;!_ATiqMn+nc*(-rle-lmb5Jekoz}Gr1lw(kQDEtBa_g&}XeoX+ z=4+;r51$Uu_C-z+qi9{yZ*VzANdwwX40Qv)}Ro z!REw)fz3ED3UM0Wlp(FgM}%isCsT()$gCiF6;Wt^PP#buy&{G&mBV}s9_C%U)u&j8 z+Cgk};P~NC;P@LK;u2u!?4fPJ!#>}kr@@C84jo}VwLEb6;9)FDfm=X5kV_00B0_Vc zalLEedRi)9kRLjNsrLNCx`z7>Fdja5c`79LYAPuSCe~DNP^xKJ%OwyXPf!JALPo8spi|3)cS zO>R!Siuc0b_%gJ$FyPXGS2t!bGUiMqL4KVml z2nuwrNB)_dv7+D=taFTW#3}b;2!*l=7VqIe)wly?sSvJeMvJNde=2#PUtU4u^AS+i zN%9uR!HTbP)maJGrp=ka7!xR*Nw~ZfYX$7Q72TxREw{pc$cFKgJ{k6t^bMJ}4&P72 z*PH=uqtw#Z;Zt%@`fd0spyZ{>`gE$0J)6w|tSY++V^6O_dvQ`Gz3*4(d02;0ktqRc zH-MFaDo}A282J(y*_`MK75iIf;0uEq~4AR0VHOA7B$w0g1@9=)W zRM{UC-%T#2{|pGSWj3Vw*zY3om$mJrJMhh4UlSkAlc>gz9y|ZMdh5KgIFVp1UTdqZ zY0DN}U9;4`WWImtlIzVGR1;j__>$UXix$h53D%UQH8uX_^Oi20huIKU>?Na#A?RPc zWbutPOPA=_(-im$4>&e&=`}U=3BSUOU>Pn7onX!6tjbb$)O`bf#Ux1rK zhx;!aJ$Cek{;`FH7ZzSrIM!bN()&Wn3Vh!d4&kKaF=o_l*pm-j3!lU@cPT$r_*N*aPo z@xQn9rK9;3!yGEe{59n_c&6hEpY@StnRs4<@|{=K;+0^nvc*R-K;hfA`O% zGcejpZ}KZFRWS;6M9Pn8P5Pl4el0?6dK#jF$e13lnHN)T1GotfUKqcb^t5O9&l@)n zAHA|?{1rO?R(E1Nd(-pX%R44%zmR`fv#W400{Sd(`A-F`xBRoU{y(FVXa0Kg&wTJa zFy8;4XK^vR|B5q{$S-P)(I0umAM&?1O&X%%hVSxx_s*Z2;*2F(o!~F)J z!vYOgVfRPneg=wtcS9{psl`BRyc?*Wdpp~y7~kAyJDK`yGT_oO_27y10iV?e{QG^t z7xn>XolklSQGM}e>c=1QSs*?CaQv?~__{ve>-&KJYaj66^a0=62Yh=Ua7%5Xi}Ng~ z3tb07;dLxuaiA3b%283@;uDUN;$Pe@TK9cfb0SAZv4JEH>cUTaQ_UjAs;f^RBA*tq ziBuyg6N{^tR`cmP+#=c_(UzeFcAfk3(7FZl>Tz!=A~D_41@-1}$<;sLqZ;z#)AdUi zE~=x1EbAuiROp+yFB45o`L(#PITU!6O?`@T0f z{66jcneUff_+N3sv2-?*Z?-mM#&^Trd+a%`Xy|Mrark-TA7J4%oW8)sH+ys$|11~$ zJmp{nj~l+o1$US0W*dp|Bc8MI-{61T1$Xo9Ic+42@5XZuD=7R3XI2JJgA2|!l!32z z!I_nTkI)SS;$i#Pz%O>e-Ta^Jg1hCR8)OgbU92=3B~zpG7zH z{Ky5TFE;R>y5Melp4J@!mdg#lh=sw=%g;+(a5w+|LZ#^?{`)StJN|GAwU_v54LAHT zzRyP?;b-8ck8-MplTLSe^IULux%?hHsy?x-;U2ijx73BljX&aoyYYX|gXeOg+On?p zzzzO|EJj=3(m-Kt;RpV12_1;q~Tuqe%S?g;~z*O@MC8&99ye{lC;7HhAC3qBo_)P&M#;+g#yXnNbe)$pZ zF4yztcf(n9Lr>E;yW#G9H|Pc=@vtZ+zOCC?guCM}b;0TKP5c{OaJozbZyA9X{D{X5 z_v;R(7yc7=jPdir{Q^C?&sgPwoAx2wKeevI35tpei^p9wu6XSDKF%h%xQL(d`{&Ol zC@s{PBPf-}Qpo5ui(~Ck=VhKv5OuzoH4|qO3`Kd8vvZ4Q50f3`=p~ueIGn-Shoij_E2~GZ%v#-&uXI%N$dw$#h`4XneMJzMoh>4>kh`=8n&C+c= zzSs?YT|XktU@Y-?46lf=vpYgN9{HARQcKn`&A(?Q=HD^Vx*PDuv9hQfdqXj$BJ*qU z=P|_2^$5;(OvK#IhF*ALD3H^5I0X8LE-0%a2+T%aCIgw$ve*6$Ivm1|E|SZO3))d2 zPQvVF$ofH(uo#mKkHLyVKt-;T{05RAf0+|grI2DIHR>gy2qlrpPr^{(atX1D38ALlH--_h zibCuMMG!khD0XA7;Z|YhutoEZ^F+A6g#4+(V_Ez_2nt0yxO;q(GwzNKObzgt%)>M+ z=P$Vm<)yA?WftxWygMHSoe%9bs}P3^0sb8zsEVE>jqf#+$aP4q-HYJhJWWe$J?(kduG0h@z_saxVQiLFYWCU}{Zyh_tRzV(5Y31Mjl@5q_9_vXO~Xo5T|2M<_IJig%i?<} zQ$8!ei&Kto+IeM397tu+)ZYAem9j`77|Nl?~kNhWYtg zZhH%Hk7Y$b&FxOyAckePeFR;LrYbpgtcqk#gvj2q2Pb#%x|^HYi^+-YHx^ zBthI&qzk+BxLg6~su}k_G=R(kZX!R(tbuJPvE`DO7X^|Z zAY;VcI)|{EH0HdG0<(zakUvx5A2N_l#he7@ls60S?=HM?*rEQL1#5Wadv@z6xE9K+ z3T64&%CcL7Ae5`oSXh~uEtJx>1{NR&m(}G;@vyW+;AUCi1}!CgC&6F?xl@J$&~uPm zTNxi(F;w2wayPCk$!2`S+f6t^X3VPgI10pdAuJiyQS3g$NjNttu-dOrW|Hk>F7=!F z?3eUvAta?{k$%vXjga}aGd=K8nuhf}$fi@$fvNlsyAh^?`AQIK9gH*u_#N>#Nr=N| zB*em4gc0PwPTpZ;^8Q$$S>7wS9#ZcbI_Fq;xx%;xEernj_8eH$s!P?17=MU zjDcoL>!3Z%(Iv#zuSCMp@(NpqlG z6_BU<A z%Xa>nF(6raMBRx{cgB-&Kh0U05UHaQBnQ%hK0&vTB(9UZ6+zwglJ=Y^7qcfDMZ9=d z;)kap99dOSx#1nKkb>ySH98sz$$>q%>Lcm{ZHW~R3{0CSxyADMi3NoM!QGV-jAgSZ zGl@`jldhPw(V#>iMCznk7Ti=!B<}xYId{{AfSxKK2!3q&?A9@$3_POcaMPzBuTdzJ zG89!eQCeF8C+%A#GRG6_IY3u0f2l@zAl|1nSv76WwB~k8I@6ki-=-y_DiO;C-AC}97N%NrrYh1^nXbARUs;r@ zl1R@+rbGJm5}K+AXW8JL{AgwfzEk>CjZX3j{5me-1~DpaOzN;EYT6Ngge0NLti+I9 zRZ%D=(csGhDh9Mtbxw$ou1=~u<+_1oKjY#H>nkGarD{TrM(lNhl}l=Y6<&M=b?zNl zm+D5a4MU?U?Y(M3=LP1I#BO?fZ6%ZtT~=AHEY1{8lt$HUKYB9}l)H*quNNY9odm@e z4+psmzmQlI9iDtAkVLorrJt^?)UJkDRyu~xig;^K4#h{)m(4_0R4np%mR~vD-YTqI z+8Bz8My@tUm|3Plt1BtaF=Z;La`FLeGBp*MJydL~1-=k8o?^EShI0`w0IqyIFxPI~ z`T-Ubu8|_3`6rfzJ>vfgC^ej>M>5Go)}8GXB;GkVSO&}4s@caOBx+OxzoTxcV+h}$ zD`mynLrJ$mhMc0%WGV#fDzQAMLxkx;Mk&G|LJoQ=wQmS_QW7bK@0R2I6}!BCwi1ndm9=h@Q>q`QYiVTPNwQ3<0TL3$1$ndqa&V*ILGuzJNm(Z$IzbYmm4J{g zpn*s>@dZeZ3sO_vsx~hyqlzLHKZ7{yq}=8xJ(N|_=!Wn{T2oi zZ?{eZDDp@-mL|-r^)HM(xp;ofy!wS#FN{7~yD)Kszq%$7eWWIyz#7Sgiz9My2iH?X zse>RU3SmYNmcgr+OQ_mwQE-$TpC5$bQ$uRN%)g3lqx96;mQIX+EW#HoBez?>5D3V* zT^`T~{iZy?13U}fw{#9jT;I|;FmblQf|JUIBC%`1cl6P6bs}AjkSRwaMjx5rpRwfn z>Sc8#P!X*55S5_-B$)KgLFkV!s1af-@e;o_xT`gA6`rhPZBcX5T}|`}ETa{?k%uSv zCt>kzHFi8aCV0zW)MP{y+Tz9wwDAnyYprw%M#m%Fls;}SMjxNx4=sZT;?WGHn>A}U z_rM5*LLLdV((iKFHBN$*;~#O_N(SH73I53oYUb7XBac)IUYx}O8p(q)(5Qq4ha)sA zp$VOon#$m6$soxLx>@jOCIiJ<|Gao)YhvMY>Iz6V%zy`zj1-fp4P-KzP5h<^)sn+- z4i9$c(1Xd7WeIiUQGY$wEZ5c~B9AXwOi{(J?ThhbAM=XBT@hQVT^M;- z*-}kB@~E;Ue_iBpEj0+l@U5p3dCQXCiupn_abiZ*L(bDp6*%u{9sLT$8H;1P0jfeg zPEF-+ip5W#n)2NdN)F|DTPyzstcb)vP^SZjlQ~;L&S{}kw2LQ36+Z`LIBY?+6yPuD zd?laaSAxz<_S&V`1?jx3x65SuX7LXCMlu;&EpCa$&q97bQQMuC6{(C^CsQi1_^XqW z(=kKB7zlEH4WRn%MN}tZV@j8wj?dnJ`p`n0;D)=Yec;K3&WWW1L5!kJ_ zp>aeC=+ana;qa9}4q2e;DJ3p;7uNx?AVT&+1`@D)B2_uOKs(S85i20ZZ{|D1tb9JY zF(ey!o0%S#vk~7jjZ~ETIN;a}cN_CKDsj~wU{>>N;IdWIz>1JH7ztQUg3zYOW#mka zgaIhY7&9SEgzxl{W%$mv2U|*Lkx5$>^$k7$9JVjZGhLigR#xL#(W)AZXVHPW^`sir zr!-(d#5%mQEec{;7s)UnLymIm?$c`0g{=I{53Ra!99xmbt8{|U$P+(Ko{;&$q{YVS zZ?Rz(_*uQKL|5k_X}2lyL1sV+nZ1l)<;Rd_J7VFVC6i5!6ZD~#N@ru7(p1B3QA_{^ z7{Y8?Fe>+`!EaZ8;JQ> zU<~4jn2^)njg3Xx%0vjaAcO?j`k^)L7Vv|*VW~zB$vmnjb7<#xG*^^X>Cr<7qZ1^t zIHFys$!V3;j9lQQ7O|N__O)TQ6|cJfd|_xwJW=Btl{{qo9av zfsrN0@j*IVELSIApll5Slm?F(I5bV8nCfd(5r_;*xyNs!=6I_^F6I>Ov zDm~r-0nw_o3Znxl$<%Or9iM?(`~b`dCbPmd_>tXn+@qFlD>=teH=z7l+0mv)`GU!? zX#2L0+24RTHS9h=n4tN>HFS0>YtM{-f)#Jkio~7=>1L0F3?C|RJt_u8D(81JyB{MQ z0;H)#TXtacFkBR$AzX5axT&k`Y*Fdh3z4?6RxS!xlmbH7BD9#pB-AVqT^yB@ZmX2E zfTjrZ2AoQ1M%qX#m6JvwN(`E*ge<+q_&9Eaib6J#Mk=iFUQ|RXAV^^`sCT<18r~TV z(W!qVh5AP{nSCJc3Lvm-GMht(eM;pMJgZv1^ z9Z#*MM`g1eLlEfUid*feb(PdgH7VLB3#r`|=sp&}Zsj%> zqX^891t+~q$wC}6Q}-J1F0bqcUSr+5sXB6^$%a zYJ_G5Sq=qW%@BE0;N%s#%DkHarvfyPi=tjsB3g~oy^tE}q^^;rRhe!bMnx*=pDNVg zEJiJ5>`LY_AP-86tY5?N@)zjr0n7;mScM~-Ih`gw2+w{QK(PDepY~YS; zy+Ln0j67<#cSoFGl#+C3ZA5}w%MoeZhvz1*bC}ro8%d>WHsjCljKq|0nTBoXe5T$a_7qs1nzMd5=*k*oLmv8YT|Cw zx3DtgtNav+U&MerO!NO8rv>~@rNHS^FJg^@q_$W6lrikwQyGhg5bs`kO(gzda$r{I z_g3;^LUEkc>>d1a{Wl|VNtHG3j-;T*r2`TMCtlciyXmp+z}bNkEt(3w1l)7KBvjZV zKE^W+UYvuizIoZl9!EA@V1_j>A0s1s1kWzSVZUl$w~%wJxhG}CiZb5=Uczz>VTm7G z>3M8l8wz|cr+FblCa;RWvsCto_mSDYo|$dt+93HCoE3B0k@a~bJXq0j3Pb*|ZT_X1 zB<)m+0ltTxFNsPuf+xs_{!PiJI#7-c&2T)B3W}>)z!guqL$K`T8SIJP3!d&-zJloT zz~ZM>HZUddOi2fkhZeOX+9CVy_Ef^^axP9TvlPoG7Bzi45*NyX$#J(RAPP1H_~wpc zqO`rLoTeY&)s=HgPkBu&YQ))_*h`GOvp~+jgPh|?f}QC%Oa7T-^PX;zEcz9F3=&@l zVWL?~hdumb4wc$>?+T@2-$EzLPJYjFL;({q0 z0x_w}ciTy{ZEyKDzFPg7evq7HDW#p5*YrIyi2_;|N(%C5{8-45<2`*xq29mBs5keK z3)#yrZMifnQHaAMrlx$);B-SsT|OA3&;WAVYTT@}cZcAQ#9xK(9=49{L-J)G9D6bn z|07()&(bqQm39TYa$3^Ag4G&(ogIy52XVYYumX!cp$g^H0;mU8K~P6vw6!$a>OfVp z1l_4hddON%Im3%OQr2KH8-3T{#F7W>wYQ<{+IFLHW3^oT7)+MrtLVvbL(~J7?|q^e zY_B~N(iZxYVt(kp;IJ61*1N5Epxt^ekm6iV#FqRTUyH;=DV=f2q_Cu`-I35x;(Neu zTh8*L3TQ^+ zBKmA(IUZtmFo_G6d_xk`y0$q&Y_MfQzotRKWa7(Kuy|blvfl=iST2brgg}NBj?O@p z0j?{`S(V|y8PfJg3@870;^d<7T&#(_-5DHAp01_)$*VypKN;-GPIK{UcL@}}iG!N1 zj>Vsjz=JKgJe5dcS;>HCyfdT}0W?1j>^RaQw`;{v>S}p7d3LyX*cpk_4B^KfipBd+ zO7d{BOS*H7FzzR>I{9r~gO1(Vohyz&$88RF+h$F zlH+a*DbHO->B&tIqXooyI4wkb<#!^F2=9v^pWB$e}f zMplU-m%&Li3mU!^N-fO_O%#k8apNBpQK>7kw12=crWN3uOFe_h2`yca6|T+s5{@9v z$yxRXmV6)^N+(Gx=;X90+K$~$63iI{e8#U?{vy;{iL9*u;7oyHy|&+broft0Qa+ps z5F9-Ivcda(JX=6v<{soqoe6{M;UM@!`tabPI8z`vxF9&Vuw}riQ`Y!W{oBw)ksp`f z->IJ&4A&o!u59qose}Eid~5or`h^A;sM>+~>~zKdjW?f3k`L%J=N|AV19j%X7p`=P z?tE}&0_f`_-GAzt2l4s@k2t8Qoj1B>!T0AcowumQ8ohW)qGmMCT)3bA&tr~J_wkUSW;fpQBG1`$vC9T~4c=00W2>PtS^I_6Lv zQq7n@ItD#{6`p*}M{i!#AL8_;pQF=Pn}j+v`5SN%9+L#fe4Jxq6Kg!6YH*}Q&CiQ}jXM&Bgrr*4EhaPgQ z@8Odd#@Hr3?alr3#^n|UFYg)uMVn(d33fSyod_O||Onh#^BD_GL-T2uMBfL<S^^1HV$kD?IS;YWN%vyh_7O9cS{Tev^KF=g+|T z-2Wu6N+{u`H0qsyYvoZ|#oa(WU8mvR6w5W-$k&~yzeTI)`MU|P?lTrl{k~GeOX-O5 zGxhdbJTv~rkpi|%efbl-_Lk@W=mY+nKHz`o1HP>f_})I?FZKcdV;}INeZW8L1I{)B z`OyANJm6>ACj+t+{5TB(KhqAe^k%@g^@Guc*0ngnsDAWVt9s%5`J*qi=8ql+@I?TB z3*d{bg`>ygy_nGoEsWiaE-JF>7AJ7-(O8CKM;Bd)I7LiU#8gG!vg+{hVyh0HB%%Irwkl7ipCy{2MO##dMhXdE+NoVQBcd2o0X=q!V;<{NLLWUGM~4 z@gLR7?!|A*UOA%*s$DXEU==sP6r-~VPv3AhR*A0JEdLt^|0$2P^ ze!Sqv`0nz4gD?0IPE|GdyIk-QF8EC>41SDH(>L+Iq5XrGo&_#AeV>Wn;)1hIG4R`5 zaCiKldf-SRzh8Rb#=pMqft&b$@xV>K@AU!iukD)UGPsE=*8?}-mU-YN-<5s9pLW41 zIz!I^7o50_PaQ&`;%Dg5YHW@7z)k#+2X5k5dElnLzqSwfG7sFe1Agp*8$3Vn1HRJ* zcbE5B7o6qQ=3^c9zzzMMd*CMD0ovah{up?!2X5#u^1w~};y&P$J#a(kbPwF%iT44& z!2>t+tn|PGB5ljM#{)NfxYq+W`HrE{;%E3UO1)ZB`hb^v;DtK=RUUXq!>{qcO+Vl| z4?Lpd-{OIr_`m1_zR3eO^!&~PH|2V`5BNKMz(4H+o~_$6UcOEDz)iVkd*CI8ZyvZQ zZ-WPJ@HBhi2G5-yxQTzz125P4e&m5yX!u~wC{wPOhF{=;oA?zTxQSoY2Ygi@@Sl3% zhR%CEaFg$L4?L#neA@#z@xSoEO?-7maJT-Oe9vbG1V6(EgD2*J&r#8=?|9$_f3*i* zspBv8z)k$SJ#a(MW)IxpdB6iVcpmk@4gEX&fcMkm9HzV`-@zWZ!SC1QK=W02q+hKn z58U(z)_dTl9lYBEH|=0FmE~vfoBjh&2J7vNj0=l;KOaTBU!b z5}GqIqD~i2^Zhb`a$W}JcRmiz;z7~73$?4_e zoP|CLL~~DX`VIzSgT*`TwU?j)#{+ziN8>v~$zeB};df3guV!{FpZ_D|48x*(3o$vt zyoES1g}n}8IGKg>A3_e!O9*!DWd4o6lZC+cywd?h!Fa8X}s)IP}plUJBo<{}Qwe;iFba$s|F zqF`V%jwK$!Q;*Mu#Afrhu)M%X3iLF-@8uE8gP8PaOG&cphhO5vQ3H;z*h9SFNN8d; z7|?bmhSxPui=VOA{uL58{Gb3kqw#km&aqf(*nL5quO3W}?0P!r94p?}bY3+60Liz|SRPtg|DZvav8=ACTkTsWOe zNLzn|I4j!|Bgu)?;@h0ctc#^84nyg2;D=hr zgqS2g_7Z?RmwPW1h>*FwJaJALGtMis8uy7MJY%<=gSk^#eLHbQU}w|ivE;oXrC@3p zruZq=JB>1*PjadGvG^-mKe6b9hehP<$Gl=?4sJcn%Q?{1K}?MgWmKtYIOptW{~6nN zc47AIgxz`ztVI#h_*xH>Y{EI*6@jB=@tu=fN^U_+o>7OGu-3-EkPg~)DCrNce9LaT z6b)ut=qA9#CM$l9ZTL?CsCh@YNpXv#l2!1_4U`R1kJ>}VLqx&;ktjr3gO8=J3 zzrW=(MBH}@X7E1Cv0HcIf#r)pGrvt*#NSX`0`EXmUV-`i$zJsn#EQf_3HE&k&~|&( z5`dsA1-l`|%4djTJS6n1mQE0KF|l_7`)H;^-lf2v^FB>wkKHm5K)m}-i0RlZpMYoZ zY)9#WXg3j>cxfz^^AF(-k}rTIy~h_E*`Akk8jmy?bt=`iWB~R4gx&H}h2sDzdQ0er z9`nqO{C?E3Ko)&Y#GpaOvp<6d(16cIao(_3#ejf?SOAdJJ=ENBk~k6Aiu35V9(wa| zWne3Ftwj*DuR09$XLFrLDHf}+M7-K`%&Ya^qDC$tCGQ9l-nN)`5|U~l3ENk_3ruqb z6X^Ks^|t2GatIAPc@tMJ#J~->l5xTfoSajHoK9u5r|VHE6ucSS%K8v!D&NE_OuO<6 zp!&!1!LE;XB{Y@m3sS>`j|wN8cQcZ*7E#q-XV&E@-&b(25$Xh7cR3mCJBtO*#-F)4 zV?o5@h_9r;J6neX-){)Px_i7=z6*{F2Z>{oXE|rvt-nM|2d8{28=$TUM(t_0-U=9b z)`@6^$so@1&y!mO?6o!cB8$C%5A~h14GZVb#(6=;S%=})Q8{JdHk{&dEq2>^h#!r& zvs_iNly3)>6Dx~w3jm*n@)`hp?oLp35bt?I8y}<}1PAhk1DC@wq6Ft6PN0)kSqIwB zr3VS1W<)Cj>LEpg&pIO+2A#7kb=?6P9aszqB7@G3WPVuQ^wjuhuKp2D6c^UwG#x8B*~gU@IyCp;P5g9WxV%H*4gg1Ow;_! zQp3{mge^l^krE7Obl$ULm{ zbUf0bJh%L8>Ht(CH*f-CtJFr8uEUrRP4At0sZ}KcZpEnl%dtPg+TIRs1rNH?mm?OE ziW^D429eUC!K-1(52?p;qr9Ac=^x+&b-NuoQ#D4WyKr3?Swcvr(#Ep5+)+oOLdawTTo)S8=loe8E&@Agd!3c#B^V>#Gui zieUqAMM@TTf*gb}X7Aw>G*i{Y6Nkc#AWmumYvEY@1!OlV>AO3GXh%XgkFD)r@Ez96 z+>VBa?~TSkZz*}=Gkc{Y=_&#TaYsCEf(cEW;rro5jYS+g?~cNI7}N$34zt-mZtY&8txL(rX{sEx!e_!-s-f z;S$lPRk_ln%YoB3kT|y2FVrTcx(r11IkRSE@ir-Bww0(Zb>6QmM@7(`NBvZTKZNDF zsA56HnTohv7jg0t+&R*+AUAF1pksS>FTsJM0XKFvr3H?;{`j&yl}@uaV00%|GL z2bUQCIicyIh;tyL_otGx;ytT-=sj+h2^^yLe1>{|D)c^85y%P_ziOvGgZ4u$$sZCL zjei(+_J^Tgz*Gl4!g?#TrXC-_6s; zv%sXcg8i|mN!0-&)SE#aq^HCTw*Oj${8Pw}-UL1ft+(WjxLDiA8=eBY!bz+~EA@qj zKZmP>epn>8_n@SA6?fXL7f{$B9UTVYD0*;c9OZ073EmV}vS$U{zw)aTUsXi4{u?6B z%Mi~?B*pYSC}VU;azwmvU#C-Lnh^oz*Xo2O96DX9?E^;riL46@K?bO^RC#y>(w|JB zKt*6kq(AIhBJ)_iY}`6)6||IhV9nhDF3H{F1t7BWC^RRpAid-h(G;Z^#IzpWIa@; zy&-G`4ZrN<6tscP0L>$m+sEBY+5+rcROH$KAUc=hhXLdq0BuvqBsVJ$7Lc*;%ev!=#N+Mq_bxC@`=jyplid>@Z_!yEU@@^GWr(fCIpoK1#q z9G$e%Gz`q_hTw#;Xzu^6gC}jW`2*p-0!xJ0XYGf8k?9J#b*i#tyXYV@C^=58nB8En z%10{I?m*Iz^G4BY;Z!KV#nx}bBtke4^{u7^^0@%W)%|4H-GRqwd^hRn?7~XeakoLA z|1IKt2(J{Hc!lqW(5_Z-6Os5aU^ruT18TC`JxCHgn>Cy{?ETxkAFf_4Zi*E(2 zs$KGIyqlbFh{Ze50ob95k}nXPzo{bPY*TA0DHcT!Oj}6^!vPu#4t_-2@e%l=cgQ?C zF7kthQTune@wvnCTKNOD+;W5jMNuB+_|58oY)?;q*A9W_APAaIP8 z_F8qcX$*r-`rub8>GTE?zMI*tCdcf8Hwexzj-(Plw>miW58y0TnunHOX?#E=z8lxW z?`BL^%e(4J41!1sw|$3_r(!|svYZa|p&_m;A|Z7R=oxJXLwvYMA%D6Y17})=(Pqd&Iv_$@Nrj@)gi;OswKtj z;FNs1`p!G(40TGiS@tGJt^VY2X!yQRYSw$aX|e4gFfTlDHkKQ2#uM9{bI^=J#=bqs z`4nQeSM9@JfWE{xK(}3wi`dk+dNg{W1h~shPOe3ylF#w&M998u7sq$t_i{t~Jc(3G z8HrwfgpChG$wyOo%*!Er(stC~jq}hUf|pZ^mZemY_(8zXZ+f14Rk33Q@+47Ud(Ntm zvp?kI+*6jy*-wv(4hb9{6y~ZG-^L-lt0)P&#gg$+)npfrp!3FD(6tjhM2n+b=>E## zSUQNs&yj;b9v=(f4)R6~Nw3DvnzB^IQ_>1!CnxtC)XW-jejKfwm8P#;(y+YLbg-zh zdjTw9L-wktVbmD@U`LMKrn&et@Sd-wvUvm~Lc)S2F_SVvtoA z2xVaRCcQ~6!bFRh)lV}@s#?UgfdyscS1N}C3A{Ft6)5Ua<@7-EIZfl>@@SyapToux z5hS$}4e@BaM0Mw01*yKzQSN@5 z1Jl?D<@}jyb#(X+*efnf9Ciza($Wte?doC_{CZ!@+H#|6^WL;^ zfDhB(7(A@kUSO^9+J4h`b6S*lpIy#-&!);6XT84pKl9$R|AuRT4WA6_O3i}~`&t7$ z^lK^tcMS432>J$|F`Mx6g&)2p?KT+ikC zX#xv9U_-wNC*wQmr>}DV3U&H&HxSPzodNf?2KWdUyy9p0MENvgE5HtPf!rM5VH z;4S~Dfc2LDk+0$deq&XT`RmO;^TG4Lc>fh^fJw&x&Dv3n)Z-^ru{@bSYDwEE8GaeK z@{gxjxdxy^HGO(YM&Hb5WyYsiegn|qxe}gY6?ou$?QIPzLR{=i|Y&Z1yd?RRc@s_)Ctsu@{_?myi=#B8wUP0tz=$!qh_5KZuYhi&b$ns zeL7<=JWK<{&x_}iKHy)aLhJZ${6o3eTf^P-pQi=p&G#A?+#Nqc!|Vmmzi3D2rSnwR znnpK0m0#}0!=e~I{J;fgQ4GAn1!t4cz<<*R+>bc?(cVat`Qhg3>biMLM=u$pRsv-1 z)hO(J%|OxE!twZo-#>q^Mxm=gP%0Uh!pG$3do@nzeU>-BTL9v?5Wvr7wO<<5M;Se` zvOVf_*sVKYZ0L6gwpdDy3IrebBSz7CI6P@T#5-CVS#AZ&X&(lOPtd3dDpUk3-0m- zFh{?=s2zQcK%tNqN#O`?=IYHR%Wlg8O72&`AK!rm1UBOdXCO?60kJXWkEWg|g)9V9 zQM(j1=6oVy2)%`2XofGF9(iO^__FARr&s9r-B7j-zy`bZqF$kc+)%naiTfrjI+I%l!yf=` zek{<8Sg~c_z|+lm3N9Opr(5t;wrnt-TJQu0Uf(N*>29caB~tdyUZMSZg&u|v%21ZU zu(ekxXR9-DGo|=Juh2&q-fj;ksW-#2>E3~;+=#_3La#nm8*(>y8Ac_VakCuUEF#M)hsH__}iIY4& zlON=UZ9CuZ|cO9lOU#<;Hm1Q$&nt!i6IP<2MRde_|SfknNH)#FTilm4Pp25yrA?; z3RbOPzvO5^nn!~nUZsNF(@xlL6b!X5)854uD(RmnSWLm%wh*>bV50yFI&E?yVm%=t zdla$_JNF-9q$&l<#j!vbV#|AC6M<88JdhH0epvw7rpN1eECu2%AD=#7Ls$kt?r&zw zJe?8*hn;&i5_ID4k||~mCEhRB6PVUO77U5+Sx4ZD3OEWS3p-aXNbl6|C_&h1Tfiv4 zBS;DmbnahG$S)KG^aq_MstHLc2q+CY4^=VE7ZIgcT?l*+HR>CoEsV$Pfy(kT6TZj8F>*dl$!1xrBP0u!9Ol3Mtg1 zgzXgADDWug+{4L@^uH+xVg;SMatYa}(y8c2!(e5ez; zp1xWGNiu-K2X zXqdm7z!x>pFu$F^Cka$#K>?rGO4zRjHVX039=&S|K--RFpSnNjtm1Qe4L%2x0ta=7 zb@QLBCN!F{5-ekdn;0>!a2tVbBy75ZvGB<6m+J|e*dxCO0W$gVIXz6}$LEvsBfo&> z9zSL95k|#ne?Shqx|3;-Xb|GTVAc_|k08Y_q`Yf2VGk>q5py$P|5GK+h#JrW4PU(sUP&0%MsGC+ticm*&x6#)21*N*__LE2zJ>D= z0s{0yTNDH|zykb)+#`^Tbq*!$HU%RSz`}=e30tmUWCLLLv&Kqatzbsj7GcvAjOC`_ zI?0|13dWLCBn^a}uV5@YV6q@BeY%37^k&}2UUlNQXk#I8uYA4#KW|xW!XJHjNgb|7UwGrZ$dfp`BT=)o-XC?I z;L&Vls#{#b?#@kxXgK?3IRIF3lJ=;uc;31T2+fj)ZD7GoPHTZal9Zn8+#Zs z=RTo(tbVxelP;Kxl`t}~CQv6YxTd4~q(p97$W{GS=d4}9Y|J{|DM$84oU?aL;%jT5 zS&|LiRjR(OmRJ21ecYp~}s)rj)p|2V4g7*=a>T!W2^(nty?_5ri*c&js7g)XczvD-dCE0qHp4^5CvpE0nAh8dGGPs!o}>2R0t%z()Cu>64<5LvAuq5>?0el{vp9+GGCh@wAY=;4>38h)7s=o?^_8h$BN!!M;J7=C#KP!7LrLU{7< z%XqB?D*~mW0&37jDh#! zCJOPmF$`XYoPp`du2?vY8|6OslGMG3q7K)_bZ%~Xm_*B!YfGS#hz9WB^eHMeSLZu- zi!1+#YmCKZPs6eym&?AGi?-k{#)A`9x|MH_^HI5MoHUuP1FYyh4AGTB8-5KuMbFz0 zRpyt#3H144kxj*a&-VipyT(`hB&}f5HR2z2()`oxwfQ}hp5jj0iN&u)&m-4R zeks?7(gjP>&}!cVd+i}vOq_vO#i~gb<1$p zK5H*jcv0sM^nX$3ZdG&rmNi$@S*vQbKd=JBod>tF2IC;Fwz5w^%TnvS`t$0o85qXL z#RLAtf*Sw)g|#&k`~d2aUhBNt`Bt&!GHd4aDHSuqmsyeEj1a?$^5~UC@^`FN z5u7yBs+b{vr$ncPtm!jC;Th3sms#aAXO&Nz9tvBNgOelSnbGf9GYzC1oB5^$Cs$Y% z7*qx(`~{{d;owZXFc@n^r%kDt9X)|NtX~--#3;BE}Ji{uV5em)-BhT>6Ir4X| zRTi8xBRs{z|FUp}6`CaxX5u+AJyc}rhq2c5NtaKXKBLT<5t%9B%;;qZ!`965;LMp} zO2ff2!FGp5gGSQedT;XgjkV73xQr$zB)26!>!GQ_T!Sr&}N ztcn<4t;ykOV55bIL@H@BiPb}N+RTb@IbxKR$B4dSN_5VZL7+o8GZvgY)e1=vi^A4I*Kr9T1Y}v#waM>@Ii&piy4#}!k`Z4 zFq{&N#TZ5xFP~Stu-ac=lSokWsBu&}Gh0z%m5V(<#YH3aTm$NK(M@RWg~dumS!Y|* zf@KgMxL$$6iF8o}3Ks#$VlZRcW%3riY|`{upj1S2WiV!i=ak13bHR(UY1Z^v73H%k zC?2xbv^J25{u$C2FI!ZzbYc9YBA9sj`oX)#r3CO{CKAFmx$4Dxj$crp;fHIrafTmH z^;7YfzEVBP-v?P?;U{Zk)JcB5oRoLP;NviV`Tb|Em8nlG#c?>+=%q`l=OyNimRBC2 zr(XY4SJL=VcsgdyE@1`#l(5qSYiLTpp<=X4d)u-w9VPj&&BEVM74*4= zrqz?Lj{Z-tq4{Uin>94vwH7A*1!!-&f8-T^CM?y@-t=3~W-QC{%ir!lru-)TbbR8o zp4!etJgC!~_~wIoH{m>;-l(yOcSNV>c!>LF(is?SMw^fUsc?)63N@7SV_K8m$nRRf z*a-Cg8mJh({7kvcrOr(iYUUVCHe1**5MBHYm}e;@Gk`+#522mGQw;Ft6P4+Bm**J+|m{X_fijZVuf z5|PD2#att_v>Kx@i>&!e>S`8S^RKB%#I5@J_`JpQt@^s93l}Hm%RyyzOL2zk{CMq> z`Wlr8w~}3Lp$duD-GIEb+6w2{(>A|=exR(;suich`k8UGd%Yf7b>zwdYLy(cG! z4Wdk@JD^{T^jzZ z5B{o#@AJX`qTxkaDHuMyui+>7;D&4HDL(il4Il1< zU!vh-eDKRP{8Ar$wuWEhgEwh-)(2mt;lK33TQ&RvAG}S&pYp+P)$l+2;6K;!&wTJ- zYk0XfkjL=h7!5zs2R}~32m9bBX?Vg1KUKrO<%6H8;otSa zO@Fq`2d~xXf9ivOL&NX&!AEQO<39NL8vd#eK3T&*^1(0F@ZKC4<1+lYQo~R5!N05F z=lI~)YIr?6XXRw}V zGCMDvaeR0Y?j2t()o??noYsgmKlQ;oH2weSgKyLDr+sj`JMntg2Y*?^OSDh7$@fhS zKivo4r{O>M!J`U&;7$!^GA}FKhViKDcRLSM*f`lME&?a?+~dhW^tu zo=rZuXw$auR;TSd%-0K#;5RR-U(Fi%Jx%_0!p%Hu9+t4}rrC%4+7Ii& z*Z!Q^;b+Sl^gr%vzbmFQ$E`sgvE-wD?F)|f91!qOK@OafIP-8X?(Q{VcN`8;eW-B8 z`hGyuIPq|g+;Q+6?nO`Hvub?qjxH_Q9J{6>wBk945qHea1q-+vm+XkQ3qNpvRVzI! zIvp0iiNu9pElK=JJ=A#RRaeelFgucZI6cS4!P296r1z||QddQiGm?)kn0Mv;rYmip zS;=t^{(-1pH2`bc`5jkF(#}u0T9R}g=4uI7hnR>(0$D5M2fj@MhSzw1TeKPv0Cg}4 zuDJW%l7r8oTy%qSkKu_n9}D=X_@m4&9(yXZ@=ZLTkP!f|hPOlxuxDwRPs(n`j?Z2# zi;f87Lo0p;NU~V5&7Fk3_m%mrR&1a1g7b1{#r1fJz0MtRXE*mWuL8QH{Vdrhh_dxK z46An|Hrlq-|2TggqO;))L8j4Z8*!#o{_%7+`W%7=-t8U@?~t<6s1rIbTmP};AOuL+ z33M0N1 zLDaFK?z~dum-!(Cn)zuehP()1XeBiU*IMHwtA+coKE7(8^2C zzz4cg6GPrK^%{@8+>9;g2rDH;_~<;l>YkSR-{cpai9ko#D_j-Z)m%aDOGRUQ^L;wY z@bxYAx8|?gO>yL^9wIi#l5I=CmJ^(6$nc>&sfg8&5eef!*_wMgUkt*rZNK45%37oS zw&nIgw1L>m4AW5h!6>KnPKItMeLI7=COAM6xu>%=560c8h~PLVzZFcF4$3m(&4*_scvwx5Py za20aall2`yfW7alOvaXTsE~K&S1MnqQRV|-WUg!o-!bfIwBJIWzfyU=9&cInr9ghs zIi!f0CSt)pnf}bQ&XXyQrlOw6IkqOB}>cPm!ap{STV8>U&c9M2H#)zedTw-nOuZa$|G_leuzHxlO7;(?<2eEz zKTocM9@TxI+dxg_;oQR>%H!NaZjd&_A`@f9kael+H>*D2U>cfx9gqm7F6y6^!>?2o zSal0ao4+Oc4KPUvB2eR0#3guSJu^AlhDZRUhoadJui7ozSjn(+c!OH1=H06Me(8Db z!N>WW`4ttT)Gi%ss1y6~t{$IIPXXw|1S+%bAbwlOk4faT`)ve3JP1HxnV$8!3qMmf zJPvTYJ03~Te%_r=O`}H;25Agrk!k`pF(M)c%L&)ve+;Ml)h3EwPZUSL9?#B-7PY>c zfq>l}Jp@!~`(65RuyY)ft-8x{XMmtL6HXLgUKeOWq$8YNjF&0^YAT!zIh0g z(Gi5qXAx1fdvlku1iEN!Ml1>S5{sB>X)kRL{vKIDven^rkb)Y#5l~i*Lekk4GLlK+ z&aRSPceS|Fp}&D-&jclOD1?6@oQvpW7-40tWg77AZrQ6@r{+`?U`H3Jb0T8?^%Y4J~n5K*|g< zfwDfHr5o}zwDpVlwL%JmT*~k^?jD1YMrJrvBDok50#u%eyc4SYfRUBTqBxFrA|t6? zv+(MpEeBCpD!0a+gA^3u(qC7{3*SW&K}z zjdp`Iqul7(^8GbPkLWq*&Tf_OFVx>FRiG;hELkIX(DUG6ZxoVs$P%U?)~pmZ%D6i^ zLKooCk>u)xlWq-+a>F>*v8wlIw+5m5pcR>@=5eT(zEhDWfL_#FA z+4OrbfHmUqW>ZK4KHe^wjCN{nrs`CjMgUkXbvpc}1=uoeB3NCmf@$UqUV9N4deTk8*& zHDWm*B(k%jUnFAhSPP6-s5RN-(|;xQRfWs#_cz zTnz=hLJAgIIR+n+SpnR^rb^uE&PQvSQ%ZfZLRv+C1lm%y~-sv9U`y; zJ&vMn1!L2<1e{N@nO;_Gz4K(|v4Xb0xp4eCNgA82l2TjQL>_@{E7_zYK!VC1U~~c6 z?+CYafW{D7ay8b55kS@{{S8&<1pG3JAmJberBZ8TZwC+=wx;Y{!kG>==aiPj+pRAl zZ+>S~8p3xW@mO64BCz-^b%ncgV3b>RbUeQeaw`@JEg20fit~~FCOfxR>{(}T<~bQjzZzW3Qh>nKbpzHsL z#MfG2qjUz@n*P*LO6}z0*{NvRdr_V#pFs(;NVUzE7ldaudkm^soNm1sQC4q6xIuXO zHz5G4;uYVMaCZ0zn5?3+HDM7Mg6o$sLh`q*x#BlC+wb6lYZUp04% zcv!F|JG%~U$Iy-HAFWZSth-(AIDr7~$&UbDTJE$`D|Wl+l+cPGY^O%`Bw|k`oGqax zZ-5t~)5$A*MWJi7Uqflp)_*awxMmG|otirhH=0w4Y@$f(OQ|N5ks^Y~bU6MzznO(W ztY}CxPCG_XtZcl<>A;}i21L`v`PG5Urb5Zov=UYHJ5~uQ;utWRJx&J@Lcbu^G9szQ zj$pgGPo@@>bG}U3A9Lig4vz`vlY|qzuhHHx+NocfaKd*r+Rt+WP==SN?pujFJFdtA zTh(~h>1bv|I8iVdv~59YI9}GO0JVv;vx(S^E>77W!ZINel*$JCS}vOC)1lTGFwUrO zclq_i+mTtPapyNWyRH5?(|*Bb=-J=F>HI7B1fJDsFj^@c3bh>tWzwlFLMvau20vDY z;wP+Ps#B&Iv0g;VaVHZF$!`onAyycd--t0{+Ic$-nO%$G@^E#8T`RNPA&KIeW3A$v zvUv9DB2>_rZ2bz$JrjBZ=NnB3%=eI<;Jjox^*=ZB9oEAh$!&!U?lHj;^RVTf zY86NOCZMt)j|_E;xp{wBsf^Ga+*v%S0yZ;>r8Hp@gi`J2@AYqB&{%b%6;q8Xlzk6x zSwMGmhZX`p{mXCs(?o&sLq1Kwq42Hdw{slPqU* z9NoL+hL_{#4e{8ngflVFdj<^LnqwY!p#u)70^$QL9ePVsY$tG_>SsWF)FR)V9kfH~)qWX)GG$CT$~1uo_j8 z>8b{AmJITn#@RK$NMS5A!VRA@qBuMxzXe^zNGCirv(77r7jV-X%BJu^4nZIYH~N7U zy%$+w$b2hLib0(w+(lmj^FL1%*Y~rEtNO*Wmq2401-chHqW4&xa!+z22$;<(YP7eHa%%oH_jQ3`a>gD96HwMD%Qu(5(XN;_4Sut%ig#-63`-5? ztDLAaLJww+Fie9dsq6(67KD8<`GZ+xzcl8RD&S7sy$)olR~XzogHda_Q{Q7%sbO=Y zz4_qIk;N51$UTXb95fqcX9l)PWRrUmdoD}{f4nf7j$Uw^|8L+oOh@hZ8i zK?$ay0PsU_0+aM`loF?E<7Ty{qPZgzcuwW}k$Ef?d0vfsC(kguPa-gPnasgC)8E{1KdNgd%@$960t{8y= zOy`$-SHkxy10!mI-RX$p;L_Y54goP#%XXnccL)e^L`;U_WVUJf--J#>Q0{(g%oi4b z=#>2mH0#fEmjOn>BI86@a8KC?FROMwnTmx5!f2ITNAtnp7fTyYawt*}quuoVpdrM;M>v|Bg{|+*vV-Vt7?FZM%>5GG2TcLnaYuJVQ(SJ5bSbdKFdgbq z)wk+QS>HtgE&mvyJfYHMmUWj14PH@(tgOYEmYx8qiBawj>OlLwk?x|q zf=(>=GByiC>re-=GULvRm`R6LroawrZPrTK{+um-wG`Gf4bz3+%OuEg5AI{^@FT1- za*>tFCdt^$h?7mZ<}YHLisfLb55CB+xox6lT&XEvO61 zR;3XXqZy1KC813rT2mleumJX>j!=5lh^|IJfp-gwkcWOe8V-cw3#C+JL7+T{|-9z@3Qsd5KG9u;d zg55KXC-9zza0`$42aZ5tvN)CePN}?t+0m5Ca!;g1eEG+3QC5}yXH#b}s8A7Me1#an z_<_(0V`v#)g4NQ#k;{0B=~@9UQ43b=D1`*@oYT?{LAQuKRvP^o{$LsuM#rZ+JmkDf zzE{J)G_15?oe7%(87mA$HBA%cC-|lyd@;&5ljTcNr8jWTd@bt{1z!}6NYiJpP04Ww z;y4&*A_|%-kD2g>kOf-@3zL%73T#?Es6JU zXGN>(LPY~T?fjr&8b0t4fVoxuu9RK+L*(AxP3||5V=R5kU8;oCrYtJeNfNj$EJ<4f z7et_F6HZMu)W*0}?D3e$6zxxV?y`s7RIkoa4c58DCrgT0t;TZRxh%nIWX;5TR0Xh3 zNDW7bI8X(PkxsauUMG>oy4XRO@-~w*Os3E!>b@Uo9zw3I0St3FN-`0jXV=K829qY7 zMfY>fJ5l$&NCpS2%_}9h#-oH-oKCfi!<9lO%iYQtr&eRZ*vIc*%%kH}7`gxY+UBU>SsZGi=0+ep*egQYBxL*+cy z4z6Nv5!}gG-of_FQ$#3@2SUddoU-3dW+&YFH@GqUk?#~ARR@ergzv~Hv~me%k!(PIofU?)ayp1y#)5+m669x9uzNY0wo6w^Z{NXOrjw&E+=)?uETqhU z!POu>9;@gZ%5Im2cC%z^_-z_y!r6%hNlYJZR?-^!!wZR`XWYg>qG%_u57>uSTp++Ka9a!UaLp zPTZ|2Y5llq7$sG@iUNPtG|IGCoQ7~r+OGM{h~k=iotk5CVo(HBINOm~=0~PsJ>QI@ zp;V4~6%6r=RZG+r?LcQGHLM7W6pK!tD?JZoEPfgm~ayjnk zY+n@_q4Jyy06LQ>JCod$J!%*w5{cr9?C1v13g0Dlp_ZaVt5Ei3kj%j^d3H!3i=rj0 zr@j1vqVAFVeY$VgGb((6&bdOGl~gcEw_>MeiY@0+qHWsI{bs&>{nS_)it|)aoX;t;tDiznt ziW7&5_EzOjk#yeIW$fZlk^Ai{EP-0ZhM^LEE3kCAx%*yL1zShP+j|xG_qj@dwE_Z% zRrQMVkQy1~H;uJR?}o>a12g-p#uta^mG~=JwVbNK7;_KI&3=gk)VuWHNm*v}=n&bW z6WfTSC*(#U86`tCo!bSMY3$G#MG!vdex~0*zp~t^NT2;~9-6oDi`>V%StWY#^e5v_ zm|SbkxMJRn8Ife_(HYu}5IHBAEv~LXbP*wYjlo4`f(LFd z9MNGX?fvM>wRyHQh*M>7gjoarG{r5aJmF3`B9O?I9+${YhOg2NEA~S3=~xqw=hx%x zLyYE1pT_}CtAH&L+Z}g;%ORtsPi04WL$&`63K@X79EN% zoS1YTq!2?fDKT$RYN~}*k#v4b210ku#0|=cI_Sa+H@D2g9bl!Lcwoj{%~u=BNgbbq zSWe%J%eIb`gEOe*`014M49}gOK$Fd9Zl*^DG4OuMo_ng=4d625I1= zwYK@3q??Y`rtHVWo2ES|BhGdX7C~Fl{+8POq9fb+13DXSE%1i4>ZX-u9w+}B6m|=p zUn2HQGiGBL4I*VDumLL*kFjg6M~nX>$b<4YpXoBYDEs%V80I<*6`U$5$ha%I7@#yui~#};7QZ%}D89A~>n$RIsVvOk@QzHxKF^#_>Xsul zyalk9VL2yS*|8XYzn8%2&I8r@jr|2p`WrbMOn;8?Z5U^hZnR=gj&Q;)9Cu?GJo5r` ztA%tvV9qW5HW*CSbpSay;hxSF)lrir4fJXb(g!8viZt0Il6_>6am8}SoIZJ+slv2Iq z5I^%SJn_7&E5cUs6aUmHg_^&%8Fz;PdDTrg9p z#^6qb)ATd!C7wuSgKccaazJ{6YRhr=LU@?s1lMOWn1`sTb;3Oj+{r+*D$>~$NKFby z!)B{)At9sO`pVI6Y30alJzNvNu(IP&Nl!H&o3ybEmA0e59hndQJ4^E(xz8fNihb+8 zJJ8W2jna%?vQg+vtu?ySGje*g;FbD_8AIvq0BNUH^(-=gN;~&cPqz0wa^f(CLlE7g zd`|=*9j#$J{u&nXZoH(BZpR(dwnWIniR3k9E<6j6!ji-GPLAh0=nwuSTUe?=3bxTo!wAuyl#Vrc6L*hJt$(c-45=a5S!FRT z;hg4<4;PP@1)0T66MHs$UXc|_=Mu4va0cmvCSp0SG*3v|ufQn#6Bx_Q^dEiPk@1#u z^NWVi&pZ7x2l&0I!3m^NxC75zlP}$gBNL!P8)fW(>~Es*ZO+^!)LCvrn5%?sEl5tf z*UFuR$cEc+grqw({}fzLt}tuPNvtK=&$*>HrR^Q(>Bi8Q#o4eeb@@fZkZQuS9#ZN+ z3g&XaiM8q-vcj`Hv}7lgt{TdK8q2*XnBN@dYTk475=Vz42ccQ+_y|Cul{9a#Ye83| z4(UZE#{(mluj)J4t3_6k$E!#?*zdm!DuC?(I*5Y$Gr~*Qckx-2l`%7pEr}3RlS<9~dh3S=0&p;i>>Q$Dj5pVH_F>nhf^&_l7V?chzoBc*}^Zr^;<35udO$XGTBx8{M| z)u0AkKLK3N>@nFwJWfbs7MO6q4EO?^2dJbIqmN=RpsWU`U}Aa$6kzQKbZ%)Pm#`0p z9wx;salb};_XwxvCm8+0&75Kmj#u+dEf)*tQAL8gICssIg zz;ofQatPm_n>!cZQRtT=A$u?cqQ#Q!Yj(Q{axva-wyxTckPd#Xc>&XWSYV%JP3_FT)Hw62Xrw+BdJa}xQUB!aEb{gtkrPNaj#Gtu6pp?fh(F~6b5lR(P-F^+ zUcutrDOeH~!OaJI<#7HAUMZVy!hs2V$h*01z>Bh7xM1##dDCZHHGf9Lo-=Fypvbvr z3>i9Wdf=i<=Us)cWb-3eUUAi&c{8S;%Q$(%@nY<_v4}i3?n2pD$3OamapMyg#3!W2 zjWurwA5?ug8Hh`7d$2ATH-0=u>iq2NS<@pCD-|CtCga{^~sChPmw3}XA)ZqE)$!qtvKPqVZI;Tr$JH$0vwj#rk{B;u@LZm zTdy&F`eph3ilEh}GTx`U<;bPzBIRPf9AKI2es1Q(<5gg zYj`2`9{qiF0iqtv_vU`7{$4k~Lh7p1VuWNmh4o#As8& z1tdmWH4k&_JmoRQpEUv-#z1VBGwGapoiW-xLEA3BYWmzOuaLLSizvVk5QvL#>Qa+_ zx>jz4mwMnoIubu{`O|OFaOP>o7EJesCq2Vp82tM^aBse65&(TUA zLwxW7Dp{ab!~Jw7Ja8}mhfh-SY9}6V zzUw`3R<*%@K*LRWIj-S#$dlg7w zLubwd_olyA>pMR^&*%#B!;jSZ&JRCb7u*kDHng+6*dI!@2cM73jB878SYr2p9GJI&YI%f61 zan5Q-Z=E@A4f5E4Sg^<7oYh9Bo#&b~I@>ze8Yj^nu@1@T;D-gr30P;uB7H-_5~htZ zv~H|nGMF9imgKUCzeF1=u~aKSSmF6OEGl{r2C%|s7M3us%y#Gx%iNY~un~)w3tILB zo91ExGU^@|+a7A$0x(UV)%~|))2bW1-f~2Lr)?QRz$6q+W*=-oDr?}E;|~B|AikD= z|HMCP6(29L03=qQvOX}=Bw!=ix|i=emkVLCv~xB!`K0PaC?H^!l+`k2G~co7gN~w?U2PVcZkCw3sw-%X}$!wsAB@I zu!IZ3C4M--b;vx-sFiW-?rvNYND^>Qgric_fje?cIAF1p}mc661?AO3skCI-fGqJY9T_}pe{7$MbcRbK3;bKm? zI@q<$sx+7CxHgUb*(qmde4PEY4U59;mSZ{rjqK9?_=^z~q;sTJVa@MPAhi$mg z4ljm<_on=HM|WbtUY;$gGBeMql-R1(wgJf9agoksos{{XNJi`9nFiP@r5@qrbqh-X zhs!e9Yu)^HN9KiTu5cUMa>B0qJr29gV;!o!X4WfUtRu9t9w<@X2nS1b4y&370-e{22 zjgBZRp|*BNkt=$~xg=twcVi$DX}WgqjB|0He&wZCoExxaAObV&pG^_5aKa`DJLixg zgNDtBs2dMjfSFNQKk*kS0vE+E7>i>)aArf~f;rbjj8PLvCkS%ZdgrxRJ?{U89^#^p z{I6|}KhVY;W4nXZ5sQg1{L$tYr`>KTPD6nGkrIcCUA5QdSVujM3*RUE^h@`N#QRh( zJz_;LTin)b6s?BpHFmd*9C>b}a`f1V{UgH$4IMNrf=+W-_3-MUk;)5ZOphclZHlC? zylTNh_4cfqp%|nLnt$!=rb{owy=k7h&ooc-X3V;DP}7WsO@To?>mV@bvib81CmqPa z2c732{2x8|K$kayJ6TpJzlJyH`&Ma<`Uh?XZXldO=;@RJ$-RUFJY4-WV$N%rPYHpz z%-EYlQNnfg@|9ereu6aIpBIOG#M#sLdMK^GKAct#4Vk|l3Kr6t{AUy(>Vau_nR|nN z=D5{+E!6b;=hdeC=6(S_A}%eS1r*Em_p1sJ^dB6p@FkK6Hf*1 zybPRjOn8JqTn5hP;%+6FaMo_uOUdKm$|WYrjx6xU`&D=6IMBA|wFR2~DG9jYffvX4 z9^jKTo>f{1O+OXTlRG~z0a6qA&Ymx;FNu1Ynb7IduCq~GR&d-3e_ zz`g0;_Q8Qlu2ZxgGISdJ-|@h`_|5qTCcUYfZ92W-f33#x!)OMkIW z|A{BPm;Wbd`Q&Ra-xhe_Ui`QD;D-J!KDd#SSA1}zU*7S-P5KXga3fbo=!{4wA5Fd? zAKc(M(FZsAp6-Ji{KI^3qu0_txJiFO5AZ2IxWRK}5Ag5$;D&zJ2RHh3wGVE}wWbI7 z?|g8B=UyM&;CaLcH}q`s!A<(7eQ=ZhO&{E(|I7zB>3iv}%G9q(f4mQF=&$j?jh?CZ z!43bDJ-{#V!3~}(dw_q>2RHZ^`{0I7HCyY{!zMjX?d4_4Yx2F_2RHorLl5u=eQ?9K zkf$Aa^=d?NWuL3^);|N&d~nlm&6{%#)_=OOMb>t2i#%u8@S*T{!S#>Fp+2O?bR?lc z=rFd(!U4?_uTKD|a1c1RL_lOM2`VK}|7IV=dn!-)gz5ctL5zp@_(DL|u}* z3R;$Q?uwS+cM|Ud0$-v6CIh}71!Z~eARP1^l5{GxEX}GV$d6{!GPxuAhTO4{pLD=V zS}FJ2WuGj|N0%#>V-N7st%?KWBDD(P@qE9q?K3!#7>va8KnO(Je1oW2j5W9sC}``0c@Y-9xv;9i$|nsEK90-8 z=kt3y3Bzd@!X@oMGEPqDkxl#OG}3U0zqKzSHr>F^3L9~mSa0ClDbo{pyTK$~uAY%^ z6;f5c0YAb&!y@}yXxaBL&Xvt_K!tD5U>2k=T!eHVARPl_9tbVF0O{~+XD7otpO9k5 z{C-IPH>CI+zdo7oF%VKhgisb$mB-Lrh0x(s_ThtEsAWBvpin}3^%I$?v>v&?5T+?< zhIr3mb0u0t&L|Xxn&X|*1N`Ru>P)Z+H+RkeZ6$Nd$WVf=}l4@qvAl z_Scwz6{%YD3LTFCtpn&`3w)50t6C_R8PxIuLaQ*dG9+QQTSa+M044ZK$2X~Bw zF_fltky&L~3@zmmkYt2tD8x>Id>_!pQ&A8^rNx{S)si9)cNVkEFg(vhRN*X3n_T}| zal$Rd?)C}Mxw>`1<+-*{7g%6Gs|J@?Atjw_F%r4LEa4!h0CRHc(b%+Fh9)R$bUq=6 z`;qb0%#L9bDpN%rNo;jx5rpGuTlm6a@%JN2(#(bvvv*%*K|V2F(cB9crNgm{44H8xc6k6OAQFIY?T#SQn1yG7hXUV0K4ze^)y1v9oPmMnzxScm{& zWF)+Om&FI3U10YTk>t2j%0TAJ^Zx@M^<^k5Z~qJ*~Y>S z^y~~8?TR02afJ>3XJ`k@ZyEyP<2tp@5bHj1qSreOB$=4(q-5>gCzU$3Ti#t3wr&vP)j`=ru}*y(iF&@ju#wl zP__CZuG9~jaV`MAJ;g^3wp%vR(u;}7nhaIvmiLK&59Y|i^&M}FS zLf!Ha-F+rH2%Y?z-t=js{LNvm9o)y?=@E8ic&{@$9$ z6`bVb!kWd1KK;7-S+D8F&-#DYE)>5S)Gc86r+)?v-2Coo?P4tr9JuzDs5|FMlxqF+ z@2*|kq3cb3-T7BfX$ycVjT8NAm&<%Vr33kZ{TeF9Sav&xDr=v=e@& zh8x?8Nk34-ja(Tx+Yj*=n~Qpqn+Q8#LU|CqMCLrG}e&H*ns&Tf?~-aPJz9=`Vf;cy~B{-2?od9^hPC=?+go z8_Vo~jj;ljcbev1dO22j=JD6z%R6(iyfbUgH8bX6iD$uFcta101?CPJG^9E(cj%xY zLjrKEp3^jF$k4$28BNo#oHuC5FgR{cA2g&Ufbq(pA;SX#JUcLB?)*VR&SB<*hR9-( z*P|QDLW(L`JDM^3YB^ooo_WRWg|iP|L_)!EnKL}8|GhF%r8@)z$Jj|Ob2g@dPY^7D z!1sOW4gBXmcvPq7u2o*Vv2B{Ql+7ME=`rp0-5%f{dElJA89YT=@A5VAn0CU5%)AWT z&@;vdH|=(!4_>c656tfYeuEEg^1Z_cH+cTT2RHdXo=_>B*4=zLhineVCiZ}4pN!1-v(`?wFTe+G8>;D-Lc z_}~_B@!Ic$n|zO!c~K`HOurKL!HwQI*#|dmeV`9+(qHI-pA0%ozUItm!+%5P)t>Yu z*}%;PN0YvWg~IiyFMX8)2VT{1Q;#P7n?888PQTxW$G}h0%jTwjjeHK)aME)c{+n{0 z?SXsgpYDU3`d#LO8#;g71ALngZus-(9^gmmuE)?%ns^=SgB$rwXt?29QY8<})o_;A zE4SBp;NJ4K`rw8?xB1|vzJBe4_tW{_c9hZR{dXDV@Ug?7yJVSkOlW)uiH|eMN;3nV2KDgoM z4L*3SB0F%u4{qAggFd*C^XD|2?a0UiQN8Gc^F6OUKDe2mzOCVGzr@3~$LnJaCqGZe zf0OSwG(yAY3MR%i+5;!dqz`-GQ4c(VXI@44Ph950fNA=Ix!tUJVr6r9^>D0hs=q_3 ztIs|gdopTjhNz=={~K$bvY}09*dX_A);#y(1=k28ppa{XVuCNM@hK}D&1*FJaxHWh z(#skff1A}2tO0HpJhw+_OQU^qA@N~Nu0zt_99_)cNWWa*${5bI#I^hmYkPMy9q`{F z_q(ENC?2>f#0z4 zv!d|vZF<2M3yDMmvo~Tod*c5JrgRh=R4n{q5aovf5-x1#2e57KlDj$ILB%}flEch) zW`QI+>N5=Q(`Z-6{+31D-vXa{u2x|A2+?5bDw_v#hXjH}>*V&c40V;?gat%8)bRY2 zat?>%b(M_EffZ%|g_wBVcS@U2=9Yv8W=43@-j?6g9=rjMfx4Ncnb%outR{wecHY(j zauBsP8dIFN_)i>4VXE{R}exWN;!x1ubzy*ZJR9ntctrQ#+?c`?)1-ZYkjwQIcq^^nHZ3`c$X(a z7d;-^8CqFKPTE_O*`N@Wavld=L7aix4=-3`(!^C13Jm=Ci?Ji4S8RP~#UcE5wtz%u zQ~wR{{+|$yG>?Y8b~xa`C}B+Y;1SD_&(Vzg99BhlTpkY%9>4JFaHBop7Ss}Iexy@z zD=hEjr8v?o!6L@CWpKEir-UdNOK4>;D3XXEI7R@cW!#arPeeqmAGhY6nDa?!$pH+6 z#$>}Q#%3$F2?ZdiAFGCRQ)HwZj5wr%QpI*7DixNp24oP0XG8x_W1v5@g+lF-UK@sM&ht8F5vZ!Gmeu*TTf5ybSVY`B+uZfkzw z!uDPiM;51p-?|mOh-aNVBQp5L=5HpQjg9usG1;0Qx?fM)PoXkb=l*+3Id$Fj*O4BJD)e7n6x*g z>DL7e}!Df3p+Mt~VDjQEuKQ3^Lh9AAMX?#80X#S23}2;mDBSccIl zdsZug%i`Eqtad_FE4O2R5ElF=hY^bxTEqDqYY>P7gxy_byI;fZt}>v+Iwn>gCSjA% zIk{7lHi2d#~=pbgSh3B)p?ItWl}!x!CjBd~X88pJsy9NC33bHpmDj z>V`lm&!3Q@w--OPYiY-WqE8lAuAbYUDyR zdw^y)(Y#JHFA+_&7qPrV4X|T=sVYz9OStc$D3Uyr0Z_h!%}4#H7AAZpkW`1s&yN{8 zlayOr`@ey&pGZ2rK#{NuKi>g^K^2n{CF)Dj_}SGBAfiky5+Xkm3RNJVQM;|dZ>*+Q z{uMYrL&{0#;!ipMOsT14-0PYF6ag+s9gBK^G8_E%)d*HrK1+!M8|*aX{eD3%xPuG@ z-cJS$Me_GT%br6fq-;6v%ybv-&I@^TjBWyp$_`HZC_a{9?iTXxV!Y+HsPGRgcOt&i zAtr687n0I1e(;5O|1H))_%}e!#9Q9RS!XyQ<5;KSPPB{~bVvMV9k8Ub6S7dr=bA9s zI2fvg??i{h!X-_8ln_2K@ZZ^EePoC)f1PzX#yn#<%E5u>mjx6Kuak-huHPCh4&zd;?A6)kXj=*C6p;W1R zpuvo}|K8f)xAmB|+qJ)5CPq?cjHUlw`%@fl(2O?x(?0_SZhrT)_E%e`Qta0WIrl>+ zT(I%?)9|lqc(ML%Zg=T=Gr!H9LhQXb*Dt~U|LONVt^Jw&xpv{bSO#9^-k_h&+=}mb znYouKr-F8tpEUF8Y3=WjF8?Hztnk--X8?_O@biT4D!B-R%j8e~(=1`WH}EMMj$4;& zyq?2#0pf=#w}H><2F7>h`x=u_-~Hc{On==m=@Om)0{xx2`M>9H^lyhvTrdkx)A7Rrjkd?`xsqjWS?t7jNsv zM2fZf7Egh|0Uz9y=wlzepa=BFw6XBIuW>XCN=)(99z>G!RfoQPQWi595#OG^t-N= z@024S^W)Sy34iu7eusOd{8p}qw8@mnZ*|g%xI;4?=(t1fh_EYn*mNY_ZOZ=~Q}q(& z3wr2Z&eA^b31J_Cqk0oOVQE6*yYUR(u*yPAdB#=v4cdmA2(mOnjjiJtATaYX%<14kILvaV z@W{f8;e4J}aSa%~8OPc6amx_{Ahh6K^1hmNXn#t!i5TEcabdL`0)3d`Kf+8Jm<-7$ z;jTR|(>6l;DmUrQ@*qHRS?LxsK^#uY=oHGTkZgc^yx`GZqkt!w7fM&Fy-H!FOOh}2 zQElJ@M&<0&kO)C3%I224;FDk*=v3uW=PG$ zIad(b!g)|U^p*QBN+C*1J}Y?UmzC?8@I^Z@LECaQkf=j@h@=!g@yaXMumEXtOY z@?E5iW>Cs{gc5@}p>fWJfuqsMDVdOMr@%X0GJ;%G^FbW93tsWaPWX!w%00C7B-~YP zak3{s;E+4zm@1Aww{Wx$Za(bmmdDWL@jE4YMj-4L3<~kfM%-*uL1wRo+BYHlGGJwS z0dr66b(lnl0SNMx$2h~^3A~g0QffAYmOYMfnV6aJ_H`I&uz6ze8=;nRfXQc3aG;io zEB+vjOGch4DSH8>`e)mUyW$mY0*k;YT#2Joy3`tYif;cbxN77NsXhUTRKr#cakNu$ z1CWYKP$)R~K@XE>RYaAB`7#+8btNKoOh z^^qpiob{1B_Ga!nsMwf-ITA-46oHA8=t^IHqV{MWT^9~ECswH{CwG)ud|{lO{wV~o zG|N1-KRLp#AMN(WR+8o4VNM8*@|<>yt_$Csd5AnE2{^BtGH@2Z9IH)NRH0;oX&Y=c zBi!K86r?IKU7o?@DvAmMx0F&+qQ%WuYTIg|CX|2pI2)D`T>_l=4xjAM@;~5vazlC- z9a#p|um<3Sd(0@O^j77bt@xH-hl3_mcJaF4Lz$mZCyQj*n`ygksV{;teG|OGS**1{ z0;6-UMC-bRr?9h;Oz;I?AV#?525=Vlk8-!riyY}Y0A_L5;a)JhsD`-Osad8-;1LeW zK2NgmKvLxqUf7|4b4*)u{UN=GkQ7S9f_*}*%OK38l=&mZ)H#Pc(JS1lK68_pT>I~H zyOfeR@Ls7whN4>7xr+mMm*W)+ApH$QFhbH6OM1QS1RBdov#iE+RZ@^r?v*G}DhQG; zT1fB5fgLF61cl21MP{x81|-WBQDOL`@$rK={B|IZEaTu=l|p&QTiJS?+@AkGha0eeb2I2+DD1$;xB*U*wO!> z-E1*w?!5l-7(r)nLV>GWo7w;R%LgLh4V#yLcH96MFT+3eD-dWf5BlDd&1{eMmrrWj z52sDcr$m3(Pv5_);phmvTr+jObphgso}w1ORd^!Kp1z+@NU0u7{s!EW&CKNgKed^y z*7Tcln*2=u=H8Rd>~8)2B=e!Zo9_&`5f6Tz@Li=ezW=$+ti&_VHF@#QI`m$%@WT(| zd-MI@vpMx-GppD6FYsp8Ow_B`=0M$Hu^p2hBaby2PW4Z?q4jG%xM_b0 z4QDn?8^wQKQ$296Kie!1+>8H*KDa6GA9{d4=7XE^a+^9YLyy68j4p_Qn||R058NAT zq`?E{V^pwW2KPn5f}Kek=`FJEm2=aA;uo^Bo@^Q{MSL zxWV7-gPZzY?t@2lzN>t2gXc~k+|=!9^kKOxM}YVk~$E0%a`8Z|4_qCJu(kopZnlOPWpP* zP)NJMbBYH}9EJ~P_~3^AIv?ENnc;(*{%T$i@Ed*bQWB4g_H158ZVjHtd~ieOUwv>> zFQ53}2G4Q&!H?hXXKv^j;Y)Ae7x~}@|HVGI;oD3f+@ycj2RG^W^Z?KM;D(-RJ&!Ww zGVppI+~6PKgByCr`rs!0}2RCv%P{VoCLwfnX+6UJ^1H*lAvj%GX#>ofbIaRR06;!7uJ>LC0 zKk~pyV_K(w#0NKe?>Qgb@c9)Vyh`IaiSVdXt4eg!deMr@Le90L-4BIa@M+(UH{M zV6^2>uh0^Xa$61sLrb2NhvLwZiSlqnXh|9m`3|O9`Yv#~3BAZf{II~c-GaMASJ~t7 zz#0()#ah0`@$zP|2@5H&!*Bf~rg7H8Rrol#2lj2u)^okDBRPn?d-a#c7tQQ~007VlmsY* zYN7V>RnGdfy^A)|g^6q!xGUerDeVZjR6I6Yy35cEdIyo-{-n46Ve~S37Q!Y?#hDJ1 zpG4*U7j%~)>8D8gbtHX?NfrH}wkBBGbs2osI_v@RHEkadU()>g)cU^^#||*?OnBJX zY}HT_Hjzu1t)58s@*QE1PN)Vi-*_yruA-gy} zC4O;yst&3`nP-Edd46uv+0BNU@yrjzd^UD}B%Q+w`F z7}-gAEf*ruM806?v?Mt`p2q(YphjL((4vqC4Gb>RT}jaSi@l%CEJC8#G{oEwvwqqM ztGsybL(W2eT=+zOXr@fa^AMQ%G`7!5HxVvQl$k7&_|}w=jk_PSLEtWwbvMZ?BYDZy zjoDy38+$~!B219XHbIs8&S|(P{>?^bb9`co=cc5bzfDX#+i*a`Uz08G)ViZ}ixsRa zYEt~(sp+^+hWu0Vs}hKyCOaXm>pG=7(_efGbmS;3TCC(ZYLy9owslst)R88Yc`5GJ zL_0s^z5|}{z|RpIPvs$t<2;_=NGv@4E8ZrHv1aSZ+AY!2IX9SpGIl^6FcMlh3t6B& z$dZB3leX8Nmqj=w35>MS?X75t7Y7j!Ppv_~J-MZRDYAJ9eJPp)yy_?JLZg-z%7$Go zPxT?HsMpvMM!6GyiuJ#8&3YY$&QdEyTzo9u zYB_0~7crb@aBQ`eoyz?J<)w5IS9*>bM!RJ2P4GCZ<%p~)Eb7zPflyl-dO;ODzad^1 zj;b}!P@9FtwKycZYZnj^U4bK7Pz|vU#_JD_2n)vsmAUGEh)i z@C9>3YS>CEaU_LWOY7X7A!<_^K-zgr?g_Lr4;A!uS@{eyWdrd@omR$i2aD@U1B<+< ztl3tpnH$t`w&sSo`*js0EACz$R8J7PgG%U{FM`l)Y0O&NkVSpeQsKF{N`D}Qy({^4 z*UARc*$Py`*I4+XL-E)_oGpWsSr#E6R3bFF7JsH51OF_DcIC1Trk z+$^ZU|XdEPh}ud6q+HTMDP%J3Dn zJzzV&pSnSq$K~9`Aks7r2wfnwlxL5py3`GIQ>DT2kJk;=97UEousY@JO*;qD&fBQD zPSxv_MiD1Y6Jt`NHX5A+jn3Yr^PWyE(wU}v0X3v}mB>ddkTh6BopJ(T5jSeAH~Wj& z>*^YoVWF!0y56B|D}DLVIL-jE+*2`lPiX0P3DZg=$76C-^4w&=8?$h4@<=X(H5Uhb z6=Y+*WUCkL&0#Rmu8I+=HyfD`uH;sc;PVvIVkPpcaf4`YlTO zKoGhhZ03o`ri}<*HAV4vk~DU_m3wYDI)=2pd4!v84LBh~gmMhf5GG5YGjQy9-cL zvWam*^ia~-%AUKS_2Xo_%(yeBh`PXbHLNr5WPZ>bF`NyRc}HoBIL1qz=sEJ+heUCQ z&No6I`VYlAY!l-UFL(>FK)?5fe!mNkY$>JN*}M^_+IDXr9fMo^UVLsuaI+P^bCL4A6@GZO>@-gvy2{?e$jCZhQ(FFiM<+9%72r z1af0$qy!Z)-zwHY;Ujoy<)4ulBhd0QGe3!EQ$-fKHl_93PJ_gO0bK@^nJIDi zxMQbzMn@To%TU!zz%993^3n@XiwdMMfu7@sP)P9`@oj+ z`u$dR9u&@#mMTW(K98bNm5aaL`b{|pB}745fTPxJ7v zNusZjIi?m_M_Ey*t$N)ckZ0VLejuvF=}ipi}WE4yHxz zUGcZhJa-{xTxK(1t9=I=!GQdqP>{#K90?FrlNEMqgd!iDc=i*o|WwOTpqkv*0+mP zjC6xH7IlbFEY2^gq)=2~FJk5E5Cic5LJm@H*VRBLdLg~kG5jFfZ}L1m~M`l^v(v+H*i}*);r+8mkndCJXMfeG4A%8d@Lp4 z*vv~RM=N^?*xf07PkWjw4FRI2bzhph1a%?!;}@lz=eth9K1AF79J+EVreG!L(NgW; zFULeQ*+6}2-A5pF$Vh`)ZLL^$`jNfi$4~@LTi`1?_{&$b;d~jp=wtg; znKN76i9uA}I>3)$P8bolZ322F z-#Mr^Q+#)Ux8wgfgI%kN;bLQg6E0|a4a#Cnw*E2H;^~}hO+M417xS5!JxYJL3xb?$ z{vI6gqvPq9Qf`e7qF9*&x^dYle?}3e4g@|3#6Tc~NDR!ptT0;c>~Ny>-ON=Qv{R@yj1cVQX=buW% zKFvIVL4S#-VUuOT+uScb1Nqz!@B{s`Iv_RWC@DklAW}BEMDIZE)CO$)XQ7%bH^i0= ztRnkPyXqk0*e<$P=gy1He1 zMlhW`=k)4s$REv07$u2S=%MIhLbRESc3?9xSVK6hJY^X6AvlIP%K*O6Vtk_c_6|vc z5kE2ZgSt4U5cV0rVTHLF2~fq-?i1N$QKGJ~w9(!*rakzAywP3j;~ZKaMlw@$5>J8I zAp#@VQuaFCM{sa`J6_O6gI5S@gyu>4bTSV*Nm46S?%Tf5?JBlunz zzl#v!L|8X?ukIwE<~Z0YtN0i-Wjcx1L=6=>2OJ!#kB-ee%*iF~nh?TE1RLtJubQZU zFoDFraQ25*?nm+DkXIp$SyXLy!+InLA>W4NXORaGUP%&K`U>vx;)yW7Y{22A%TVwq z06}JIl1DD8$s4VQ{qVi83VmHZxWt&o^1&6lk~)*C>7Dx9n5|&of=N7p7TSiYb2zDh z$N2^fN-^3h=ZH%vLeao&b2@|Kx+<#b$fcldCqQ7e48-&65_Jg}1B9?p+hAx7B^|8Z z_e-I+tuKrE;HC!uLnsC>s_0Y-a^)5vQwf674uGPYomj4Te<|nQ`&Z7?Fys~$Z`0N*a1^eo3PUSnH_X3f;q16yqx}LpChSW1Nl`~U_Nj>CfYK$pr-IJSLG-F1k5gVo-O9I_dsFs) zAUZ=Rc7yk|vge=vQ6N(ds1%kQl?l-XG7|-!{4qp)GQR3+uV5i-Q}!WBYpg>HD~tl4 z5Ot{SMF=g*;FXidGs9Ki&H72(TX@8A1RE`i*=2=G7*!}vOdDto3x_h#8>C22@wGpqQ-c=r2wB^9ie{_$8|zZOAP@(rSNOdfN|>;x&?q@hGGG}GRtIzw#@P)kH2!pe5)9i(~-&CexKX1+9DCfYaQKWA~Hh3h?vEXbTv+pI;=0~-z14d}^$y=#NkIH-%hz0=0vt^(+F*Z4b2dsN_ zRiGeKWJU7G+=QAo+D|Ho++^2afcmb411~3XqK}boXz5ItwTx^@9U%Xyukq<=Jn8C& z3VDVF6x>uV)k<|U**kbKhN= zeGY`nEQ;tSY{Rgpp1Y|!o0YIw%c$jiQhc<2&Rz=*soO&HShiQyhf19(3t#Z2qK?=X zP=krkfT|_R4&rMkO4dafSuAxuzNiBuco~Sy;Rg2=!vSG=u9P^t#NWvZcLc9xGC7#D4{{@rpm@ zv{WLh17Ia684pd}P0}6{@rN$Kh^rt+x*4b*Ow}IKKIavFv|ENwn*204D#ipDAtwD5 z5RBbSO|zi2KH;ZM6eYm+9m8hh7eZ~nz?P@O8^q605HUcVMb3HanIo9Y9JT1oEylV_ z<{&15JO_M2YX3~>eTz@;HfCin{1VNKzV)izE@1zXvHcs8ErCfy)(fYRcQVPJXv$GLBRAevh=i$apS=l~;q z1p?ci;Pno-tl%od?OH590|9;a!~g&PeeR0t*W0d5eEt7p?_I#7s;>X<6BreBWTHk* zTdJdu8X!gpK{F<524-M_6QGI;EoyKGf^w4tMT-*@5T?T`(1mlHQ8Bm{_XF5-(R2SeV+F`kaOlU>#V)@+Lv?AoW0l9 z=~jhf7q-lsa&Aj_YRj}LZ~T@&_;mFSAySL~J#bo7n)uN~cgYsq3B zvrA)6Cz~_upYwQ3vz?f5nR3;{AtQu{+LRyvOMNbNL(^(|DtE{&VO_ zXmir1RB?Wc&L$-|-;VvKQ3kTjR_DB)JV z8l7BBFYcW8!=Cg~{mb)xJ1CzkAWe2I-d#eto3Z2zo%3e9=_UG?oAh?!p9W)<=h4{C z2b}Y#_oSOglI1HkAwz}@89t;sTyY92T5?KTI5lJT`~~*gqid=MdR|rQ#k1O`oP&Ma zJiDJRNAp@{PN`~ZSGQp+^qg65 zoY`>HN(?bqchot2q;&f6iRHW}^~7;A)oZ&^r7K@@^OTRKevnRm{u(~NR?3ynkn}}? z%$b$3(Zc2YH3E1q=gXctFiN6Y$u%5h!34#{9NC|O@9CJEMNxV+pI@QAkaR_`2?yFI z^xgPrR^oZPGybP8OU@VnQ{P2gZyQjpceRP#^4&}vXhz@3`PARIo0j#PGy6|Yf4+M% zj`jKUS-HrZv4iWK#HgohA^BS8e@`%7cSynW$I@TC_gBhw`c~?je@X6tbIvT;O>;tJ zlYCKkM_fM3p30jzcZbfIyPhjLfaS|L0ZHj_=2Cxz({OguPv_Alyb8y}!vwL3J>*{E z6^8c6AJ2RUbCI|0Ea25DKAPnl6d%hx$z1F?oq0-e`q=jyy&&cuvix`@pJp!YTl7z7 zK9S|cewqVI`E6z{@)t3ms(3qd(np)fFTpYCp>{``@GOpr&o#8i&onBQ_yXo4e=YNc zir>V1k>bB(PU+JodTzxr>0fSW5C1LmmCVHt_cC9t*U9^ck zPvV&PEr#~^;Th(4D*k8YYnh9lH<&-5_`A$EDEKvy%<-k!BwvG=lU=k4uVGHn zTU=hxoYHqW-BVJ!VZ~F-D-@r=oL*tjCiYKePU*Xxj{ENN3P+rJ(carsbG~_)>h;A8 z=8{kO(%yIPR_s@Wx3YY>0NyWP9#;HP<`s%x&U}dC%b7PQPC@u7vSqE}tC%Mhzn=Mc z#n&)zR-A(Ulm6+7-_Crl;&(A$p!izm%N2i!`69*tzF)2t z4`My`XG71E=e|Rk(`xHO_1%s3ZI z`n66)bTB-w%)o+vbMcT~HO!kmXZ9rsk1(SOEAq8Wn~|Nu;Vx|XD(kQz3Gv<$P68HT}rQZ{Uu6&pr57zPzp z!;YmRoNcm4XAh&ZYmoV>nxS6H`BgPYcy?9IFz*5!!*=`~j_?rY(oYvPSdj4iSwpL8 zj-!2bRZT6V=rf!^`{A64;hc%#)jBi;B1M>R5jFHhl>T5zMEYwa;XOJw67U-xA8Y=a zr4QjK5cq`t4mW>|44grvmZD9}GDT{R=FYSAQ*iz((oPy}amI$z03d?8u+t$iMDzIutwYXqujKk-oV< z-x5fE2jCpq4p4lE#onQcb9d?uQ(W#3Vm^GV5C6X6qJN&^qJO30wQT2&ipQDXs(6z5 zeGZR-iT}4doctMK`BxOLWd4QX^~`tM-5!Xah3})d*tx$C|E}WVhe3*q{+Po@zy!(H zc!yKIME-Qe#h!B=?)oR=aMBa8+4Sf)S=uDO;-3!1CEedDF6DBs;$qJOic7kGQe5=> zRdKQBABu~7AO7)3?3Z-=DK7GEY>xo)E#-2Uk{3QqajEA&P+a7vC@%7P?Mi9aOO*To zQyQN4W9EC|GsQ@d?OMe{{DrJ_De{u;uN?goAuILjw+?r&U-vtl{3Cj{`tY|L?$+B6 z9q#&huYT5GU0!91M>t=4txGA#8Xx(wK76U-QeHpv;lFYCB*$;}INZ(GpM3bA6|doZ zz2k6K{}&D?{UX0VKPrmfr2d2z7x^mYQXe>3Zxs^X&mO~u9jPZbwEd+~Fqvz_}2cp1HD!6x}?HlOg0+~El@(SNSPM>)LJ;gs%F z)^myC)0y9-cpLLyD=zX6D87K@pH^Jt-|^vJD?XF;^zUyE#1Fzx_u(@Xm;5eKTF{t)_X5QSGykEZhw8YL`(lTm>hKi~CqIb& zH#+=eN50G9uHRl#T=cx-a97W_%AgdR_(AeJ#D^yw?&>+!;jTT?efZ6ai~qMPzS)}R zz31>0nE3N!hf}(LWci~Hum_Sa;dKsga`c?RT$is6DPm*Ik_&5D|13w3TfXxheyXEC z<8ZQ5^3~z+v5x%x4tMjlNpaD$-QlhtkKYq%Kh*p1QHpQn{NAJZ)66&f@Yj9#`-baGt}d zyhP706c>AbqqxX#aQJvf{}zXnezAYM;-ddehr4!u>~Po4l5!};CVu|2{pjtfxac3` z@X3%BKh!wf)gMz_^p90s%5jnpPb>aB+c`t=cbU&oT>Q37ak1wHAO2s82e|&+;luA$ zT+&^yxYVmZDlUF_(TBgOxa9X!#l_A&zhxaF!_E^JQ`cHPh z7gd~Zo4peir)M_WPFDKG&hZYP2sx>56CLjMx6>R>c8Z>h6c_uKD=z-O-G_H6E_z;e zxZ8f;a5&i``cL{cK46n_5k6jV(SN4m(jMnJ+)ei)hr8+CqPW!0wTer-_`TxKTeH2# z6_@(_SH(sC9mPfeel*Y*oA^QGk5XLZYkc?^AAX+V;E;lJI}us;KOGt{s!w`sJP_! z3dKeLFBBK~ZHh}h{EOmJuXZRd^<*zI@2RK${F&`MNO6%5D=zXw6&Lx_6&L$k6#tUb zo$tecsJQs&M~X-I`f{D(lJ3ol|C7^wTXC^xhY$ZsanZlW!B(NPM=AG^;z71^fDex- zF8Qidyo~iE6qkIRskr3pe8t7i3l$eXFHv0NS13M!?YUZUvFA66i~ffd7k|F1xa9X^ z#U^V|#sn0*~;jRgnxagnl!!wGDKd(~!OV4h<@Zq;AF6DKf z;?nLOR$S8kNO4K`3m@L^P|s}AKZu_F6qow&9mS~RI<4VOv{u;%_|36n;?72^I@!KPcOTGQO;*#Hw6c;=9IjncNh@THsT8(~6_@(+p5oGfe(7+x zT=tG2GuXtRqGzBFKV5OLXNuyYXRhL6&&7(1{51}r47;TM{KVk_aFM@RajDP0Q#?>Y zx%9mCii4z#V&*?`hp0H+k!`ix#Nh$(*I55b#sA6tM#aVdw<|7s z)+#P~-cVfnfs!L_LXt135B(IEdfs1gvF8xQMNf_5Qa_JZT;!V+|C0T1s^TJlY2P0E z-QPoO;0s$HTpnh9)Ep?!vNiL8@C{Tr*w&c8G^fVO%X|RIw{V$1P)Y!saGB4LR9xmi zEK*$N4{T6e<`3*pT;@fzwzSbG`8mgg?KX7ikZ8^DnrQX0K5Oh$*AB6g|Na^~;oWTB z=x>8LY`~I2{XAK8BG{08==$qud+emfb^HGP=*zCV_JR|V*=twB=*IOAWS_tGuI)G0 zH?GaUckh}{AHDO$#{0j#^@HtA=Zrrox$cAMe_ej>&Nog>X75`G@l^KOxn_40&G1QO zmyx4V+0LEVCGVGL2g!$=RA?E;#`W@5uKlPUs|?MJ({2cG`cPw(ivy*`yayCIc515q!=VTGR2-Ku?7jsY8>%Nn^maTzPXzN-=)0@x2r>`l}qB7^jXqp>F=B!jI6b;cf*H6-sJIJtAv#}zwH zg8Fi#*tlNQH?BK;#E*kNyRoZIDjUV$Ty_gih0}JJ-Ljq7p&ZFplq&tggw(@kcWnj1 zwW6f){^F6fW5YRO$9ZqV4r39q?6nhdV&i%PsO;96Bd@f9!=9L0uxyA)q_fuSmNigX z+54!;!;bOTbuGIG=Nb1dyAwy&udm?a4;EFqO*jQ{kD3Y}V*8Z^Ux1;}Z z$&!rBcH0x8N%@%?%`xy>GMGbv|!)%icD- zYjfQb>`l?ndwJHKXt4{2Ety7qT?8MEj0T z`6H)4fj&5!PHR`bBk|WbQ_|$AnNr?${>d-9N`Ea2O1pxX*>w8C^`7MZ=P?y@EwEbq z?$ScCd)I}utJnafX;*WL$uI64(_(w!o1V0p6K8IKj4@&J_nUPV;xnhr+QmK6&|Tjn z4IMtbrpDYP{rmSwJNUgmnb2VD=vjxbP+WcR8LZ$%;p4F);4f`JX{<^{S20?bXF9D6 z)=U9;v4+`=k+s0I`rrn$U&1Q^uHcmb?=dR?(&~ZZDL6INa|$J0LCXu`-UVT*Y1P2Z zbS|{wP6m;=DACu9wtLJ%XOw8ztbaDGYgq%zmsb#s<;Io8`i?8jPuR0hEP6(HXhmj! zvIR?@#pu$3sFiz|`NfIcq}s&bNu`PWsT4ys5gLb(=;mfImiu01Z1DF2Hg+6N;b5qA zRM@n1duZH;w7A&lppD3APijAk*F~aeU*WF6??~Fl-70j&>e_=g%vuI(#bJrJ+=zfZ zt!_kRsFSX)Huxh2IfDafF~#%~@m!#@DJ_v`5m&a)=v>*}9KLN--GqI-Q0FxmI>nK~ zD39SW>9VU3_xVa2tJDURzLuiT7)WJgo}A!K6GnVV_ErQ3>NaptTK zLzNtNE}l!4a+L0PU9z_QL~#UG)-%Ba;fPeaY&jNixGK7HVQ`=+BAX>ss$yBJ?tsd2oduJy=1Xgl`XtYIgaHn>Svun31dM@tRH4_Otv;4Hu{w$W!F0> zY>d^7<0a)X&r=k_=2)(wHU^I*a^ou#gU1I3ZjMK{E<`N$1z0SqEz&UX$wF5)6ClSl zJ3j9@jO9)aWK9Xi>P|-0dK0N}#iRt_(g~62h{}0q&nZ}uhC|L{8J0vY*e6-?cCkeI zg*q#6X}A7NW*@bdn}We=Dr3{Zt42oabC>SUb!?+eyRLucSu2Uf>0;T`gPdc8h#W*_ zG+?!9}!w(*;0v&(94yPH^@d4fYuDliD&Guzx#mrdll7RJjtnQM^_Q|p;Au9Vs4w#6}^ha2O zfV=oH`LdsoYZKAb0Vt=NaJNDo7y4~fb_(NZDwn-#6zf`|Zc=6Dm(+h(bWvnriS`+{ zIb9fvo%g*nkDOec>c?0C(OV_oQ$Y2yHp9o_|zs zz@DSB146~q(I+>igFjBs(@BcV zSV{StXl$V@vL_qU^~;kR-=glJjvD`vL^gPQ@q&jomP`llB3t6Q_D8`zuO9xGr? z7hBWn#x-P?Cvs2SbS1RXvtH^UgNsh>?t!Z zZk;i^aqYR`3+7LmI&VsHUE7Rw7$Ff_nzH6{gxXG(zA<~PQ|Z%fGcKHl20*pGrC9B8 zZNaV0Mcgk@K5;LTAB*M9tcNpWxaLUK+ak%4*|IC7HK2G>`C$K8uB5~?O)O{DKau^G z?c1TM&=u|CyOjSfwg9*V%UO-iPX1A#SX{PfLLG~!D7f3OZcgTdYvZ{RZe_U(uuf_$ zx}&|R=w&!~OuGImRNaTNWjVGNH!X{CIlux|rlyF?v1lAtUNQ*Fjs6ra-;#)K%iQg{ zd{IoV#We^yu@m^QutHa032a0|HCj*^6S(5C&djswG8)UB8n7i9t2-6f&Ix#ak((s6 ziB$TDk-7RGrPAyq^dU=0c`S!M1ik#yeIQRNv7AJ3|5#mW|3E1J8A{OBR;nA*Z4*Ra zbPys&^M^XD>m2I57LOdo$gi)A$ORXV$OdoVW|~abT!p;cLyor=^>S6=QRFO@-fnBR zxU4R9wU@cQr%}YRrw4eQ)}FS8hW?;OeXBLH&i2{)Tai*>1NBeit(92*H$C7AtOtEv zF_7_4X-smbY-(fyt;AFbtI%32t3ri3so&%)S^Be7I*A7%UnADAXhr9gv<8gLmn}!V&h2IEySbnl9~7Qk z{COX~pXj&+=k_Y76=x6`4wtc4X_;N_Z=)}?AFJw*ku&!uY*$x2KMIRYO0(Z;^OW6T zb2xCbtq+;qt!Jfv7K>$MHYfp!*+bMVW`jSn>Z!^%=T9%O6{7A8+^OA;cS_P9;oDMk zOJeRThT7oUa*hADgsd<4wj_>SXe$MWfAOML zS|hTeD`6^JB6n0zLrE-sBXe5urWrjJRz$g%To=m?I51W>`M|)!GOCqHwDbMY&i6w* ze-vNK9R$_jo@;TU?hvjPncL`cUJ+YdThbP$?%h7NB1|=YOLtb$>$Yj}wUM;pI><{% z(z1(T+_7Udm_A4zcZTy1K^r#BmiuBXs2Qs}&Nj}>WA9vpo9=gw2>l$BN}I|;Z3&Bm z&!n4+H~Wmp4X7?WJ|c_NLf=_$9wX7&&<{vncMa~WZ4K?d3jwgTpF$l2ivpx>d@B9n zn0(N9D~IWxb(8lAEW|?NsYnu6n?12K@ScH7_hU!(qpVrwZkPVM?q^ImZn&z;bWPoN ze`4d)hso>HVOuGk$$c3L=RqWmA=#@ff#c-TQ($v3oSKtFzDvC93 zDhWlRe}rmjsePpDsg36L+1xnOEjB8XSvbbHneO>F?D8&H)Q1KgO%};xVrdOpd9S+8 z+UZHt-m~Lg`(qqqO<5=Ixip3Das(0Q3dQ|C?)|^&iI~o@_5ojprGuWLKW3$o&&k%$ z@aHTnE>3G2O#TX~JZxz(=}BKmvRHEpi<8(@7+Pr+a(g+rW1}slVw<9*KcPQ=0h;s% zT(rFe%koTm%C>Y`0?$6@$3l1D@nbSpYrvueumz#YC(^`&1Uk?4||3xU2AX6c2BF56$lW zv2)tOEwks$Z+z(7>EU@TQ)Y%6ADq=PYtFoj!)?h2=Y;3B%$qi6UUL1c@TrLjsaO-L zKAr}te{8}#DYLtS?vER@chEy&WA>(I?C@MT9Xq=QIr+D|YY$ji=)MWD`N0ta{@9sQ z!{H-_R}GzZMA{oWf7UrI^TKncA+9_>CwPkJ#{>*L*pEGmL`K`xuGDQV5W~Y(ER>TRXRA#hY9EO5ZXCZ7F zskbTPp?8im^mkJCO56X-@3Q`nanOsQ&wGVM|IfVavbpub*i+W=?AB{*;7{T|`BJ!irgvt$ zdUJ3KkAvOGg@IprOgj3V$&t+ILfvaKJ!LOqKIpXQofYZyJKsDDIcg+*K|^ss`L7lr zdrtom`OJH%CbDk;r(^sk-D}&-=ZAaIo_9uK$0_)p&Zjo*Zg2DX6J3a7IZtpC4zy3` zyEW7hu*thQ@;|-ClJkX6W{zF2t-*Oe;(j6d7B&+Hn$dT1evJt7Udz%g*Eh-ztc}y3 z|1ZwpmG9^jnRisn&Y^psLHMup@AuB`mV-%)=Y3{(#lPDA;uq?G~`geUB8>7 zcWo3uST@NQ`IESOmOYg>ar0Xrj)hY*B`)uKht0(k!dbE*IC*Sm_N{0aozcieJ)d>dTrCS4!+aF1VdBe3w4Su+q= zc-B-z5gzKzYQv7=`chb5it3BNx(FzI2?7ewnzA508$pF<&S-6$T@^L^xfE3x>!u(o zu8AOA?Lh>=ac9k(WhM6nGrTuniS5m(oS=QR;_>CbTUo}b>~pF>BpOq5-T zo=Z-_cBkE$>mKzTGVYchENG+aA=P1NrzPC+3YYr4x8l-%5A)#_ikDGh*oOM>kv@E! z4?kOR=|3f2wb(B_tK`KV`Wc5dk(c`UYajlg4}Vy3(f^p@Z8kaYX~iYo*Ay4~KUI7@ z>*+&=V-x#@hZGk*Va3IsBNdnWP^q}+Kf&QgAbqJ_Amz@dd&ej)?a{u4_@3__xhB)U{N1p6SvYz*Sc#v=9#6NN!-l* zoa~f()u4DYC%nqxuAb{1PI}~ev_^5!bBE$m|8?AI;hUAb=y_Ig>3_adT=eWsKLTJA zKMOxxaq+_-#hcC9o;OBu(Q}3mzr=@MHjZQT&|DH6_@h8!H56KhyPA-(f@nJMgP-^%k||gA1+G@i9bbtcYbse zF8Xy`X^|i7BcF4)+wQJ&IJG;;*KLZ=W&hu!xY)B!agpDmxX8bxxX8b)xX6F(!@pKs z^psJDhfVxeYCn2MDlYo#6&HUt`S7Veyw!(athl6mh2oO#PZbyWUn?&8TCcds|IvrP z=)>PqT-x2oic5dB+uqi(;%DLCR$T09R9wnyg5q&5uPKU)e_DO`QXhV;;*#!96&L-# zR9x)Wai2xc{YqZ+JgRsF=j$28MgL2R(>0j3e<(i0V(*`di~JrzDAN~u)E7_i3D=zx)Qe5OWDlYQRDlUF_ z(}(X)KbT_^|A);d&)Y|FsXyQL;bFzao+A|({WU&3p}6>eoZ_P2jk`_P1*s=)+->3! z&ew%X&jRL)6c>5>Zn?)lV$ZcoUh3^n6qoY4RdMm>9g4@)JjX3?_+W>(J3Ig`{>iFzXS4ne#UqN6c_)W$N?Ip-w=MX55G)t(ch`K=()>>Kjg!o_2GMRLfX!Q6c>92 zDK7R*^Whix@Spkcrxlm_@Ur4b_P@j>mwK3E{wd1~XYB1qF9xwueviU`sh@{9oa#dj z{?it5xLdC(9q!hvVGbuf(vIpBPZ{laK4va<-opGe#Tk3k96hf67dqUv|A!8D?O*J0 z*Zxk2lOD128pYe#pkF91<#LuY@|I;$Ay>j>Q?e%{|7$&YsDpB2b9@_ zbh!+4xa;Q{#rdOmk`KSt;ckDjz`5?YJk0r~*JfmsY-R}Fyj{$Bj_!KSbF^kyHO9(e z`}gNO&y_}qL>o-PGUvG|`=mSP*_rU1%H3mTB`32BBXd)^6=qs<64RYA8o-?e4e~Zr zrZBg8r`hv7X`EgTNt*bK0i6#-!sY`8n9~erOnk;%uOy~GSI}JNwdTazBOA=#&YY(C z(G6t8YXmW06_X>DL}(Z_89{@hc~&$=LSm?<8T*>VEbJlprf0mVKEjtce?^4e2Gexx zTI?}e`0*r+!r%xaDcGH(cew;+S7wfp(W~}69z>rD_Qe?EP{$Hj zoxg;qJl9?7WnQq83wYc$jTC=a@`Q=Pv4Ia`)brak?Dwe>nfHOAzfajQycipMmYMnd z_Ow{&m_easEf|(cGeNhYp6d)Ay!55a(Z%@=7~xJ6=@PlJ5KVZ>mi4m}w8U3+$7i1E z@lHHiS6=3q)=a0&LmeaFo)pTxnI;iTPvpk(PwO#l zlkA%Sy9xPp{;x^-%2W+}Fy(C&FQr~6R*%_XZu{qI?5-ReiGB+vlJV__&JuXzteu5O268;@vnU_&9D6AeDIKXZol~8 zeYvPF-QRXx4DG2sbAIBs1<1UgmDY8bRd%}dt}PF1V*5aD`i<$bEM}|NuFZCfU3F&9 zlQN%U!LC5gbd1K{?$MZ*lUz-nnP?{k)$bv;mGQ(erxwjZ&;GI0JDS>rI+{$TKSM=& zpeg+nTZ}wkO=Xm;KhPRn)QDIOTiMA2cVhnRKDogDcD7|7(F>%e;snO7WF41 zVF@~rX^uWU-ch%gnaF_XW;bhoRiuk8nqe@Xpd@X=|Z(>|l?LEVKH5GZ?=rmPrM zba{D+E*dmV&87~)GoFUnq^FR2S>)wFM67t>FE0;>kX(@d+V6@i5TWU9n_EL7&83we zT~eHdX}Vim$(I&FOGeRjD?8(ot`I}Wn6FJ36PW%r{y*ClxQa5&7hx`^#`G5-jtG?o zp2dacYs`GHola1`!ILXK=Qy>t$QbX9Bxfvcfz}-YeOk> ztuy}LE7VCg*b+;ow`MmsrUO^Ta)Cv-w4a|`-IyDEeu3XZC|o=Tf8r z!>G*5;k4Hq^Yy4Wr6<7!Z&98PZ@n~?exV7IbUqx3vU{aC9UcA(;lAj)SQb<2P2O#z z!<_!C)UmF>6O;#g<-vUcm#TF~Ji85HLNYRCor*4r(urrw?zc_7JB@xcKb|LIzVjIF z(a=5fb+kK!nQ=Q&X_%=t!1ir#BnpH9??n(^CojpyhZXX@UP~a z$l9R)r#UBa%s5%R2Pg6W&p9!UXkd4U|M;UPTt55FIceYmTExGB(c=zXHTv<1@>@1N zZxc5+?ff0>YWH?NIEVCn=x&wxKsx=-pY95?tc!-?1EpW>LL5u_^6V;KlPqnrZ{TD8 zDT2N-+eEgXvoE-qfAPa9_=a>*dvLeueEvii;#kfT+=K(|6Z&pL#7c;t$^TTv<$U4v zEH72xo?-uP@bSOoTV!YAKr{MI&aV+c-fLO8B`<;7Ca{tLWCsGHKFglUo4Dj(_A=*0 z>Z!=vb{QzfpA=rjdZhjcKbE<)7vU!|4`WZ8@KHD>dm@JR@G;CQ6d%i++B=Ot{{@bTPc^iM)5rhKIUcu}^mgY|dvvp43>xNuHe)lkg*!2FD1mSgrtjhU&@V&-x1B#t(k z%W<5Ul!56RWlYnPb)kYkzoB?NfBuK!(k>6-4vh4Z9;v^B6c6+HV|;jv;tec+fe*h}anY~mT!@|5 z`^f*shu`bNHz~f89@?<|QSk|E|Emrs8^!;Bb2#};+HnbAe8iu^gNlou{S|M3F4_)O zT>80M#T$$?e!f&(s3OAN~^`{$GlV{)ZG7{qHG0nbX~=c!YTgUySK% z@^druy%ZODzqt~JDETDoIa2X3^BToPf1To@XO!a2tmkyaMNf<3lI|=Y{v*Z3&sQrh z_4Zeai~ipzF7gj3UeETwq_~vV-xP0V`F|)b^8Zv^>RGR^oPeY zr#lgPR+a4}#Sh>wnjAfcgGs;L>Tt4C%IiACC11BHF7kIP9_Ms7D&EX|i{c{xwBiw# z*K-{%aH${WmEt_Yb%G@JAJwd*-c*huLp0DqhC?O~pmN zgntZ>au2fneu~GLmn&Y*{7A(IFdweCw3nFTV&`bZ!>nh#;!?hP&Py}PpQYr*|L6Pg zj1OO~xajXxT=f4$aVg(h6c>3t*GBrcbxL0NR>h@#y`;Fv|5b63e_wGa$Bz}4a{NMZ z=_mK-XB{r}C&m5`DK7SWOYs_(Kg!`@FwtM-@Bp~zndfj4QMOSvyq zT=aJ+E`Io#4}Vs1vHuOlMgQLXQ-ahhvAmwKz`+KBv}N?!c`d&Q;Pw<#Vr)}bCME_(iJTWow;3 zclMmAEyY1m#kI1A?|MwsaYLe5MeBbyCTan<4N9}YBrId18nd6qPH)OS8apjEp)vc% z(~{Y*PQ_9X<%nx%U*nOvw1z_|y?mO8S8_)d-zXv=F26stZ>tI$>JmZwW;OF-ZoZ=c z;qnKXF#vY(MOVO#Dd2$zvBHKpPUL8LnU~_Z)0|TgQ#w2r#W>795zeZPH8AI}DUmpd(jAt+1lLD6wkY8pLJ z3QNNF73PRs*$pEHm)#T__&G*}M7M{QEP`yItM1aUeV2*BFNq;NFFyaBBQmTWqP+Aqriw1r)@Tpk#sd&EfkXYeQ^A~V*_e!mc!)6mD0bN`gC|6Sb*EK^R+Q5zrgTb-2@(zY)92%;qrrGSR^XC~ z%GwF-7$rupWjOof?(v8ynfL67E?Z`Whw~Q~qF->cd4jFFfX7`#KW!hzO~HOcwWfJw zwtls>g>`I*=f8*X8$6yO^CzgZ4(OhO<-jBt6`>WU;Nz}x(S00#GDP9q>Pf#JX3Du? z#|N7l)HAROwJg+0A!Pa8IloMgei-Wfy&37SjVsoGD{Zcl80BLtmPG1B#rp2Qs#vH< zT(f47>uoh2_-yt?R6&fHT6!v3z?H0%hFHX+FL6!gPN;nZHBQstm?Gm0HKqUFn0^?| zZOO=J&F!J3d(pWF>PrjNM0s2jE6O|~qv*PKhfkzR9}O>dKY%~1pNpA$q>cpN`2-xYx_|S-PPu zVa;wU<>4N=Z)Ck<9rg z)1rzpe)cK?KG11Zf|E|a^HWNJKHqO_ggo;%sPn~s$_s4`_)o`rY{f*jU-AhNv&ng~ zr+aofMsLw;o6F}<>_vP0CwLqVbe`zDHT*-Mq)+}Qm14i}vzTMoYuoJOf3aJHXX8LK z`cBT5XC9H)vVLPDzU1^Tk`sBa&!^AYcO<$~#&&SUpo=hFKXm@-QB2nzAa7@X`s;cB zWp~BDI{o4o>VV|_H^)X$_UIkCY;r_nbcoAm*?*h4#bFzyzk#EB>>2Dy2P52LSOgwIA4`0kYsW^T7-yG9m_45NVr%k&Y z{<~uoq@TYATz+pQIoW=SgI#e?9-7m3bOMG1n6UvEVPMAwd?U2vjG;6rp&FwS5MZ(u z5g(&Q2ZB)!@mgokq6ct_E;)NBjZSEtT}{IiT3hj{20MHjZh}T4x};6Vj7$KoH9;Wl z6Z|el9?&=g+NiIfvXb(W@)j=bV+;vn)BH4xzrmXo7yUA_Q|q}*$xFJOKKus7MgMJz zi=GWW{0Sfan&P7WBgI8OD!JJtU(z2O=);dtT=b0c;onodg6;T$;?nM06qj~CM{#NQ zdaQ=D@5M^Kfz$n|;$h~roHlLZhp_qNdABPr{#>hggynU7O!3d3mAw3h^`7D)ug7Yz zdQXql5IYYb!?B6|V$UIpOWUVaKU{gq*AT_yR?ItA@doB6DlX~96_<3+P@L6xXDKfB zT&}p3?<&Q`o|_aG`}J55vGZOfFZ?;hrM&*CxajXzTuU@uOJLuN9YeeW&8mkFQl+ z7y;`|#Hl7d;;;E_!wD~TBcfR6vVD({ zi|h9-EF5EhHesr1%ZuJ4F!;2NG{$nO;JKJCg8*|O_;(~-Hdl~~twHNUknl^qG= z^sC&LeP@UHclJ=n+4ylhXWj@ceJ?wQf1jp&WsVWMw~WQKYqJb0*goEj(*?C@=PoUo<>A%ju-*2okzVI+tDUNme>g(c1lKbEMjg{&Z z{gx-29MLt7xO|p9^*h8R|HA2f|KIp_RWnFlw9wghqx$6jW>;*t#fw-PzqSp*Y@eZ+ z?NiM^h~e_a=S%yivLxGNo(R2oB2Sv$m`$CMBWUAarB6Mmye#O6c;_OC@y;buDHnW&J|wl6uz$y zAE3DCAFR0OIl+gY?8C!+B7IFZ$<})DtZ7ryZ5MpwUTN5_$43nvKIAwXH0s}v8MRX` z-bl2;B;4SIaJLjYqbb`(F{7HYf1>eGU!K;Ok4J*1CbN&zAgOq6bXmOb=u!&Kgg+A^ z{gQ~`v=#~|IMW8RUlF;J_Sry$!r&k*$IQrrSbhP=BT9Cetah13(q%k@Aqo*^{1b)7 z`3-5XL#HT?17hhQmJqGIJGU$F5WXwE+ehlF@v$rLBcjEjOsgVPiATu5sRX6KOFkpW z&FE~|Wvo2~vzHqMuG-$}5TxmP((W$3p29d3JJKc8aVl=f60ps=ox)&&%uv3ABisAY za=&vM(;s1-@VgLc=yJJfjMX8y1K(F6dP^@Q6l94ih8=lAx$lSQHVCh9Wvs3~Vh0w4 zIvv`i_&SKOC7o`)RFqZRA3AK9@?v4LMC@*`z6`&eN!?j+IkA>e}h6A2b^I<%Gfu!G4n*Rd}vKzluR-|Vf~lC$GJ9G z4o6%0)TVDgVT{c&>_w_Ciy+&S-WEd~iZNIfU4nWb(nQ%7q`Gg}bD3>iY9q4?v9|hf zoWP^4VEG5_$788j3Q{p~EKbMmc&>2iQTfvg7}4~sy~}Mc$5Qu3BLBUwk(pff1Bfjy zEc`QDkH8cU*|M-JbF^Pf0ch?qbwWl1)i0)6Le(sle$x7DR4&lLx5J~ef$Mt>KFXGL zSdADE!XwB?BUQ*`dNaOdy`+?&R4*Q2v=Pg2qe|?9Z#+^nl%{1zAm#z zRt_?-)Ll0>EPWkByXy2io1Wi8<7jH&j#1a zI5?9xF=rDw$(Cgz7rzSHHz%T-GC${Dv628!>i|yRFPtiF=fvRKR8E8f%zs#{+qQYhg?K-d0EVTHNy3zCBkHNu_sU zq?_BtzwWlmqy1zn-T=G)yxi=n{p8TMP%LJNjSx5IT5h_dsR!iY$CoJ_)10v;#!MJCU z5sP`6k1myRh3VN%s~T`6;%XItS9#KmF_f5e6pYgJVrX;-%v5R{To+m&bfNn*<;bmS zRCd5sTnx6fsc&k^FB}eA5cg2}WCSNX)?Pdk*^u=(Uvk=#h_3YjUvjv_%N94LKjeJj z%=_$_=$4jCKV<|*W`o6Exa|O2nknwXQC{ez*YmZBaztG>B9zhn4o9EDP-pXS8R{hW zcOOk1(0VCHv%lUgDRd7*332tP#S;+!wiY`hc6wv> z3A(?0#NJ=h;QIZALs&8 zj-TKH9o7eQp$Qf?MY&36o+sd3Loq!5Skr!_4$++#-C>pE#%BzLU88H4DP=58UpE04 zWb+||d$d5L=ek6{92Q`TZK%og2Z)q)U+y3)oV&=}fqfu%VB1g`+t7sr}lI!TbP|FHUc}Nw5B@UMZE9eSymp!ZK#I+iVtaixQ03OHQbx1ci+e zzOGX~$&8W#y14BvMV0umZ8o;fat-97!?zu91XswyhFD!7!Z*b0w6inw#nGQ7^ED6B zX$XmVTr9W0^?0oA)WD@jBXXW|c^{n%u1sWu$4bv^Y=~upcUo2438z1cW!oO)dl*XA zsXV#lYFyx!1-?;-#049XyWYPYo9dL_J~9`?y?W7ColB@EG7XL@Y$<{jW&;mNmbPI! zz)H7ET2EdXPMO3_Y$F1xLS28G=Ez)XA5R8MkE~0D0yF~NTon;N6xC(&Gdr_2>w9-p zws%5VB6R8K?BuI^lv|r{W0t4X@Jw=0;L;<}E2Rf4?zt?kMw>YBn_e`DF6BY+q0W<0 z9VAB|P)~@byW;|dEw+HnEn6&bkPLY?Q*rGV$U*j{x+4v!oN#y9n4zRjT@!`-st zY~U$m>ND^`^aHCav(^eB{3vE2jLfDm_}|oR_Df+4?nl>Jgdym$I&?C&WrjLvOgpAH zL=tGSJ&oH8(Ki0K52RGYoHewba(<|M0dD&Vxh)BZ8S`6up9VueRgLwJ;UqONjnW-UKFA^6_tZ0e=}w_dbb zOy`KmtwYBdD1$_=ehPOexH&^A#iD7-SK_wqG`<;$<>sTW%JRe7z~>5G#S-oKIZi8f zQ&k+7)!el-rk_Aa)>OKTI;b}4pg!Titn`dnvz0oi?^53A9-`Pmp>Mju_D!}hY!xr2 zFhuf*-wmeYkp`V6I^@O9^C#j>F8s=)Bo;p6WwzQZy)@0;>TNpR zf9{z~fbx_%U?1ZbjxTT}D$R`x;(bxiJEETIP}qp8r76Eml~lEjBXVs^@jUXiO?Pqq zIs~CyfL4z1p(pc09J=0lSS1wsJfb3x>bc{@T0{$@uc@pDmBw*$SWpv zN7F>}^V} zoirEC_&#!zY3=HYa`5ZS(^+KIz`BtA@()x?z}yWz*SguM0N+T(w5i2mVxfF?^+ ztk@0nBu4eGUA)H?yN~Wa-in!ZBPR1P?XKV-mvR1x{^cEgJNsasMLrensDS|M23#=>9`k=s)vL&Q8Qgx3=wKR)#Z4gTDRGyuJ$~ z`*e>Yeq(QV4Setx4fuAp2IrU#{odWJG5sIj0dOUtmPG0Fqm!_e+nskL_QdtOw~GB) zK<(sRfM6PW`xE(md6yw_L)iYX0Nzttw8_4S zkM;TE`Fzu7nKSGkNmtIF!snyc>$NT5^EdaRJ^mL=ZA|-wzFU2~l}Os1N99LpOZrlN z=Y#F)4O4@341B)q#BTZgLmX&E-^uwkBFK9!>-X-ljniN9FU}`@+IMuyTFziUc20k= zBk*76-|yYy2Cnxnkuqn~_B&toIwZOOFT8ssH_S)P57xeCN7r^ z;S-rleHDHt^IGg_6MhbkNl(3@J)Ewp#2XZ!%RH|5h0K$RU&=hC_!8#h70)uCpg29E zl0B3^+Qj~=a7=u%p*?&x^Jc~AW8ZIFWvo!&UG^X(FRhK0@orZ!F@IvdGq+24eK_4+lAdP1zmXe|$C&S6Wpe-Vl#d>-`0}&&JNB7~ zz&QueH_x9tujL{{-<&a{>R4|YX0@1kDMK;K#Y}@i#7sL~#m)^F208XTY6rAYUrTkUoIYTq{+~AC zGG@U1G~#f12d&?&3*Tt8^ym@(iVuI+hxg$QTI>-$v@#EEn(J7gB46brf0E*o-*JkI zp7VV8MLwKsk8x_ph|(*NptB$Dojhc7kgsNsrgZw(qoKr3PEuU-Clwbx zrzkG+=lbwV6_}anYmaJ&620N?y2*bt!uOsN{v~7?`5xeI+mTv<1SAI?_t!sj^raAZpCxyIpSi(Ch9QC!-oj&&)1yI;wN*>QhVT=c)7 zxafE1F_1l?=Pf1A>b)I4JitF7i2p@?Z^gx)Zz(SFhbS)c0~HrLhbS(35{ire&r)3E zFYw`cAHGU)vGeDOi~d^_7khrIxae80xafIBap|xA?!&)QT*|#4KeX%e(lIK-obb1O z$+eE3Sm#hz;wm-hH`#U

Package