35 #include <jsk_footstep_msgs/FootstepArray.h> 40 #include <boost/random.hpp> 44 #include <jsk_rviz_plugins/OverlayText.h> 45 #include <boost/format.hpp> 51 const Eigen::Vector3f
resolution(0.05, 0.05, 0.08);
62 void plan(
const Eigen::Affine3f& goal_center,
68 goal_center * Eigen::Translation3f(0, 0.1, 0),
72 goal_center * Eigen::Translation3f(0, -0.1, 0),
76 graph->setGoalState(left_goal, right_goal);
77 if (!graph->projectGoal()) {
82 jsk_footstep_msgs::FootstepArray ros_goal;
83 ros_goal.header.frame_id =
"odom";
85 ros_goal.footsteps.push_back(*graph->getGoal(jsk_footstep_msgs::Footstep::LEFT)->toROSMsg());
86 ros_goal.footsteps.push_back(*graph->getGoal(jsk_footstep_msgs::Footstep::RIGHT)->toROSMsg());
99 std::cout <<
"took " << (end_time - start_time).toSec() <<
" sec" << std::endl;
100 std::cout <<
"path: " << path.size() << std::endl;
101 if (path.size() == 0) {
105 jsk_footstep_msgs::FootstepArray ros_path;
106 ros_path.header.frame_id =
"odom";
108 for (
size_t i = 0;
i < path.size();
i++) {
109 ros_path.footsteps.push_back(*path[
i]->getState()->
toROSMsg());
112 pcl::PointCloud<pcl::PointXYZ> close_cloud, open_cloud;
115 sensor_msgs::PointCloud2 ros_close_cloud, ros_open_cloud;
118 ros_close_cloud.header.frame_id =
"odom";
119 pub_close_list.
publish(ros_close_cloud);
122 ros_open_cloud.header.frame_id =
"odom";
123 pub_open_list.
publish(ros_open_cloud);
128 const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback )
130 if (feedback->event_type != visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP) {
133 Eigen::Affine3f new_pose;
138 jsk_rviz_plugins::OverlayText
text;
139 text.bg_color.a = 0.0;
140 text.fg_color.a = 1.0;
141 text.fg_color.r = 25 / 255.0;
142 text.fg_color.g = 1.0;
143 text.fg_color.b = 250 / 255.0;
150 text.text = (boost::format(
"Planning took %f sec") % (end - start).toSec()).
str();
154 pcl::PointCloud<pcl::PointNormal>::Ptr
157 pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(
new pcl::PointCloud<pcl::PointNormal>);
158 for (
double y = -0.5;
y < 0.5;
y =
y + 0.01) {
159 for (
double x = -1.0;
x < 0.5;
x =
x + 0.01) {
163 gen_cloud->points.push_back(p);
165 for (
double x = 0.5;
x < 5.0;
x =
x + 0.01) {
169 p.z = 0.2 *
x - 0.5 * 0.2;
170 gen_cloud->points.push_back(p);
176 pcl::PointCloud<pcl::PointNormal>::Ptr
179 pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(
new pcl::PointCloud<pcl::PointNormal>);
180 for (
double y = -2;
y < 2;
y =
y + 0.01) {
181 for (
double x = -2;
x < 2;
x =
x + 0.01) {
185 gen_cloud->points.push_back(p);
191 pcl::PointCloud<pcl::PointNormal>::Ptr
194 const double height = 0.1;
195 pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(
new pcl::PointCloud<pcl::PointNormal>);
196 for (
double y = -2;
y < 2;
y =
y + 0.01) {
197 for (
double x = -2;
x < 2;
x =
x + 0.01) {
201 p.z = height *
sin(
x * 2) *
sin(
y * 2);
202 gen_cloud->points.push_back(p);
208 pcl::PointCloud<pcl::PointNormal>::Ptr
211 const double height = 0.1;
212 pcl::PointCloud<pcl::PointNormal>::Ptr gen_cloud(
new pcl::PointCloud<pcl::PointNormal>);
213 for (
double y = -2;
y < 2;
y =
y + 0.01) {
214 for (
double x = -1;
x < 0;
x =
x + 0.01) {
219 gen_cloud->points.push_back(p);
221 for (
double x = 0;
x < 5;
x =
x + 0.01) {
225 p.z = floor(
x * 4) * 0.1;
226 gen_cloud->points.push_back(p);
233 int main(
int argc,
char** argv)
235 ros::init(argc, argv,
"foootstep_planning_2d");
238 pub_goal = nh.
advertise<jsk_footstep_msgs::FootstepArray>(
"goal", 1,
true);
239 pub_path = nh.
advertise<jsk_footstep_msgs::FootstepArray>(
"path", 1,
true);
240 pub_text = nh.
advertise<jsk_rviz_plugins::OverlayText>(
"text", 1,
true);
242 = nh.
advertise<sensor_msgs::PointCloud2>(
"cloud", 1,
true);
244 = nh.
advertise<sensor_msgs::PointCloud2>(
"close_list", 1,
true);
246 = nh.
advertise<sensor_msgs::PointCloud2>(
"open_list", 1,
true);
247 boost::mt19937 rng( static_cast<unsigned long>(time(0)) );
248 boost::uniform_real<> xyrange(-3.0,3.0);
249 boost::variate_generator< boost::mt19937, boost::uniform_real<> > pos_rand(rng, xyrange);
250 boost::uniform_real<> trange(0, 2 *
M_PI);
251 boost::variate_generator< boost::mt19937, boost::uniform_real<> > rot_rand(rng, trange);
252 pcl::PointCloud<pcl::PointNormal>::Ptr
cloud;
254 nh.
param(
"model", model, std::string(
"flat"));
255 if (model ==
"flat") {
258 else if (model ==
"slope") {
261 else if (model ==
"hills") {
264 else if (model ==
"stairs") {
268 sensor_msgs::PointCloud2 ros_cloud;
270 ros_cloud.header.frame_id =
"odom";
272 pub_cloud.publish(ros_cloud);
273 graph->setPointCloudModel(cloud);
276 std::vector<Eigen::Affine3f> successors;
296 Eigen::Affine3f::Identity(),
299 graph->setStartState(start);
300 graph->setBasicSuccessors(successors);
301 jsk_footstep_msgs::FootstepArray ros_start;
302 ros_start.header.frame_id =
"odom";
304 ros_start.footsteps.push_back(*start->toROSMsg());
308 visualization_msgs::InteractiveMarker int_marker;
309 int_marker.header.frame_id =
"/odom";
311 int_marker.name =
"footstep marker";
313 visualization_msgs::InteractiveMarkerControl control;
315 control.orientation.w = 1;
316 control.orientation.x = 1;
317 control.orientation.y = 0;
318 control.orientation.z = 0;
321 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
322 int_marker.controls.push_back(control);
324 control.orientation.w = 1;
325 control.orientation.x = 0;
326 control.orientation.y = 1;
327 control.orientation.z = 0;
328 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::ROTATE_AXIS;
329 int_marker.controls.push_back(control);
330 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
331 int_marker.controls.push_back(control);
333 control.orientation.w = 1;
334 control.orientation.x = 0;
335 control.orientation.y = 0;
336 control.orientation.z = 1;
339 control.interaction_mode = visualization_msgs::InteractiveMarkerControl::MOVE_AXIS;
340 int_marker.controls.push_back(control);
344 plan(Eigen::Affine3f::Identity() * Eigen::Translation3f(1.7, 0.0, 0), graph, pub_path, pub_goal,
footstep_size);
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INTERACTIVE_MARKERS_PUBLIC void insert(const visualization_msgs::InteractiveMarker &int_marker)
INTERACTIVE_MARKERS_PUBLIC void applyChanges()
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)