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
Gepetto
aicp_mapping
Commits
60fe8e82
Commit
60fe8e82
authored
Mar 14, 2019
by
simalpha
Browse files
Fixed vector of Eigen::Isometry3d issue.
parent
f6ecee7a
Changes
6
Show whitespace changes
Inline
Side-by-side
aicp_core/include/aicp_utils/visualizer.hpp
View file @
60fe8e82
...
...
@@ -38,7 +38,7 @@ public:
int64_t
utime
=
-
1
)
=
0
;
// Gets
virtual
const
std
::
vector
<
Eigen
::
Isometry3d
>&
getPath
()
=
0
;
virtual
const
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
getPath
()
=
0
;
protected:
// Set global reference frame to zero origin
...
...
aicp_lcm/include/aicp_lcm/visualizer_lcm.hpp
View file @
60fe8e82
...
...
@@ -38,7 +38,7 @@ public:
int64_t
utime
);
// Gets
const
std
::
vector
<
Eigen
::
Isometry3d
>&
getPath
()
const
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
getPath
()
{}
private:
...
...
aicp_ros/include/aicp_ros/talker_ros.hpp
View file @
60fe8e82
...
...
@@ -3,6 +3,7 @@
#include
"ros/node_handle.h"
#include
<Eigen/Dense>
#include
<Eigen/StdVector>
#include
<geometry_msgs/PoseArray.h>
...
...
@@ -15,10 +16,10 @@ public:
ROSTalker
(
ros
::
NodeHandle
&
nh
,
std
::
string
fixed_frame
);
// Publish footstep plan
void
publishFootstepPlan
(
std
::
vector
<
Eigen
::
Isometry3d
>
&
path
,
void
publishFootstepPlan
(
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>>&
path
,
int64_t
utime
,
bool
reverse_path
=
false
);
void
reversePath
(
std
::
vector
<
Eigen
::
Isometry3d
>&
path
);
void
reversePath
(
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
path
);
private:
ros
::
NodeHandle
&
nh_
;
...
...
aicp_ros/include/aicp_ros/visualizer_ros.hpp
View file @
60fe8e82
...
...
@@ -52,7 +52,7 @@ public:
void
publishFixedFrameToOdomTF
(
Eigen
::
Isometry3d
&
fixed_frame_to_base_eigen
,
ros
::
Time
msg_time
);
// Gets
const
std
::
vector
<
Eigen
::
Isometry3d
>&
getPath
(){
const
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
getPath
(){
return
path_
;
}
...
...
aicp_ros/src/app_ros.cpp
View file @
60fe8e82
...
...
@@ -294,7 +294,7 @@ bool AppROS::goBackRequest()
pose_marker_initialized_
=
true
;
// Set path back
std
::
vector
<
Eigen
::
Isometry3d
>
path_forward
=
vis_
->
getPath
();
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>
path_forward
=
vis_
->
getPath
();
ROS_INFO_STREAM
(
"------------------------------- GO BACK -------------------------------"
);
ROS_INFO_STREAM
(
"[Aicp] Follow path of "
...
...
aicp_ros/src/talker_ros.cpp
View file @
60fe8e82
...
...
@@ -10,7 +10,7 @@ ROSTalker::ROSTalker(ros::NodeHandle& nh, std::string fixed_frame) : nh_(nh),
footstep_plan_pub_
=
nh_
.
advertise
<
geometry_msgs
::
PoseArray
>
(
"/position_controller/footstep_plan_request_list"
,
10
);
}
void
ROSTalker
::
publishFootstepPlan
(
std
::
vector
<
Eigen
::
Isometry3d
>&
path
,
void
ROSTalker
::
publishFootstepPlan
(
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
path
,
int64_t
utime
,
bool
reverse_path
){
...
...
@@ -41,7 +41,7 @@ void ROSTalker::publishFootstepPlan(std::vector<Eigen::Isometry3d>& path,
footstep_plan_pub_
.
publish
(
path_msg
);
}
void
ROSTalker
::
reversePath
(
std
::
vector
<
Eigen
::
Isometry3d
>&
path
){
void
ROSTalker
::
reversePath
(
std
::
vector
<
Eigen
::
Isometry3d
,
Eigen
::
aligned_allocator
<
Eigen
::
Isometry3d
>
>&
path
){
std
::
reverse
(
path
.
begin
(),
path
.
end
());
...
...
Write
Preview
Supports
Markdown
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