moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
plan_responses_container.cpp
Go to the documentation of this file.
1
2/*********************************************************************
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2023, PickNik Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of PickNik Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35
36/* Author: Sebastian Jahr */
37
39
40namespace moveit
41{
42namespace planning_pipeline_interfaces
43{
45{
46 solutions_.reserve(expected_size);
47}
48
49void PlanResponsesContainer::pushBack(const ::planning_interface::MotionPlanResponse& plan_solution)
50{
51 std::lock_guard<std::mutex> lock_guard(solutions_mutex_);
52 solutions_.push_back(plan_solution);
53}
54
55const std::vector<::planning_interface::MotionPlanResponse>& PlanResponsesContainer::getSolutions() const
56{
57 return solutions_;
58}
59} // namespace planning_pipeline_interfaces
60} // namespace moveit
const std::vector<::planning_interface::MotionPlanResponse > & getSolutions() const
Get solutions.
void pushBack(const ::planning_interface::MotionPlanResponse &plan_solution)
Thread safe method to add PlanResponsesContainer to this data structure TODO(sjahr): Refactor this me...
Main namespace for MoveIt.
Definition exceptions.h:43