Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Humanoid Path Planner
hpp-core
Commits
f2b9436c
Commit
f2b9436c
authored
Mar 14, 2019
by
Joseph Mirabel
Browse files
Use shared_ptr for typedef ProblemPtr_t
parent
5ebc43f6
Changes
4
Hide whitespace changes
Inline
Side-by-side
include/hpp/core/fwd.hh
View file @
f2b9436c
...
...
@@ -175,7 +175,7 @@ namespace hpp {
typedef
boost
::
shared_ptr
<
PathVector
>
PathVectorPtr_t
;
typedef
boost
::
shared_ptr
<
const
PathVector
>
PathVectorConstPtr_t
;
typedef
boost
::
shared_ptr
<
PlanAndOptimize
>
PlanAndOptimizePtr_t
;
typedef
Problem
*
ProblemPtr_t
;
typedef
boost
::
shared_ptr
<
Problem
>
ProblemPtr_t
;
typedef
ProblemSolver
*
ProblemSolverPtr_t
;
typedef
boost
::
shared_ptr
<
Roadmap
>
RoadmapPtr_t
;
typedef
boost
::
shared_ptr
<
StraightPath
>
StraightPathPtr_t
;
...
...
include/hpp/core/problem.hh
View file @
f2b9436c
...
...
@@ -50,7 +50,7 @@ namespace hpp {
public:
/// Create a path planning problem.
/// \param robot robot associated to the path planning problem.
Problem
(
DevicePtr_t
robot
);
static
ProblemPtr_t
create
(
DevicePtr_t
robot
);
/// Constructor without argument
/// \warning do not use this constructor. It is necessary to define
...
...
@@ -289,7 +289,14 @@ namespace hpp {
Container
<
Parameter
>
parameters
;
protected:
/// \copydoc Problem::create(DevicePtr_t);
Problem
(
DevicePtr_t
robot
);
void
init
(
ProblemWkPtr_t
wkPtr
);
private
:
ProblemWkPtr_t
wkPtr_
;
/// The robot
DevicePtr_t
robot_
;
/// Distance between configurations of the robot
...
...
src/problem-solver.cc
View file @
f2b9436c
...
...
@@ -180,11 +180,11 @@ namespace hpp {
}
ProblemSolver
::
ProblemSolver
()
:
constraints_
(),
robot_
(),
problem_
(
NULL
),
pathPlanner_
(),
constraints_
(),
robot_
(),
problem_
(),
pathPlanner_
(),
roadmap_
(),
paths_
(),
pathProjectorType_
(
"None"
),
pathProjectorTolerance_
(
0.2
),
pathPlannerType_
(
"DiffusingPlanner"
),
target_
(
problemTarget
::
GoalConfigurations
::
create
(
NULL
)),
target_
(
problemTarget
::
GoalConfigurations
::
create
(
ProblemPtr_t
()
)),
initConf_
(),
goalConfigurations_
(),
robotType_
(
"hpp::pinocchio::Device"
),
configurationShooterType_
(
"Uniform"
),
...
...
@@ -263,7 +263,6 @@ namespace hpp {
ProblemSolver
::~
ProblemSolver
()
{
if
(
problem_
)
delete
problem_
;
}
void
ProblemSolver
::
distanceType
(
const
std
::
string
&
type
)
...
...
@@ -466,7 +465,7 @@ namespace hpp {
void
ProblemSolver
::
addGoalConfig
(
const
ConfigurationPtr_t
&
config
)
{
target_
=
problemTarget
::
GoalConfigurations
::
create
(
NULL
);
target_
=
problemTarget
::
GoalConfigurations
::
create
(
ProblemPtr_t
()
);
goalConfigurations_
.
push_back
(
config
);
}
...
...
@@ -687,9 +686,7 @@ namespace hpp {
void
ProblemSolver
::
resetProblem
()
{
if
(
problem_
)
delete
problem_
;
initializeProblem
(
new
Problem
(
robot_
));
initializeProblem
(
Problem
::
create
(
robot_
));
}
void
ProblemSolver
::
initializeProblem
(
ProblemPtr_t
problem
)
...
...
@@ -712,8 +709,6 @@ namespace hpp {
void
ProblemSolver
::
problem
(
ProblemPtr_t
problem
)
{
if
(
problem_
)
delete
problem_
;
problem_
=
problem
;
}
...
...
src/problem.cc
View file @
f2b9436c
...
...
@@ -71,18 +71,31 @@ namespace hpp {
// ======================================================================
ProblemPtr_t
Problem
::
create
(
DevicePtr_t
robot
)
{
ProblemPtr_t
p
(
new
Problem
(
robot
));
p
->
init
(
p
);
return
p
;
}
// ======================================================================
Problem
::
Problem
(
DevicePtr_t
robot
)
:
robot_
(
robot
),
distance_
(
WeighedDistance
::
create
(
robot
)),
initConf_
(),
goalConfigurations_
(),
target_
(
problemTarget
::
GoalConfigurations
::
create
(
this
)),
steeringMethod_
(
steeringMethod
::
Straight
::
create
(
*
this
)),
configValidations_
(),
pathValidation_
(
pathValidation
::
createDiscretizedCollisionChecking
(
robot
,
0.05
)),
collisionObstacles_
(),
constraints_
(),
configurationShooter_
(
configurationShooter
::
Uniform
::
create
(
robot
))
robot_
(
robot
)
{
}
// ======================================================================
void
Problem
::
init
(
ProblemWkPtr_t
wkPtr
)
{
wkPtr_
=
wkPtr
;
distance_
=
WeighedDistance
::
create
(
robot_
);
target_
=
problemTarget
::
GoalConfigurations
::
create
(
wkPtr_
.
lock
());
steeringMethod_
=
steeringMethod
::
Straight
::
create
(
*
this
);
pathValidation_
=
pathValidation
::
createDiscretizedCollisionChecking
(
robot_
,
0.05
);
configurationShooter_
=
configurationShooter
::
Uniform
::
create
(
robot_
);
resetConfigValidations
();
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment