footstep_parameters.h
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
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/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab 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 
37 #ifndef JSK_FOOTSTEP_PARAMETERS_H_
38 #define JSK_FOOTSTEP_PARAMETERS_H_
39 
40 namespace jsk_footstep_planner
41 {
42  struct FootstepParameters
43  {
50  local_move_x(0.1), local_move_y(0.05), local_move_theta(0.1),
60  {
61  };
65  bool skip_cropping;
66  int local_move_x_num;
67  int local_move_y_num;
73  double local_move_x;
74  double local_move_y;
75  double local_move_theta;
76  double local_move_x_offset;
77  double local_move_y_offset;
79  double transition_limit_x;
80  double transition_limit_y;
81  double transition_limit_z;
82  double transition_limit_roll;
84  double transition_limit_yaw;
87  double obstacle_resolution;
88  double goal_pos_thr;
89  double goal_rot_thr;
95  double support_padding_x;
96  double support_padding_y;
97  double collision_padding;
98  };
99 }
100 #endif
jsk_footstep_planner::FootstepParameters::goal_pos_thr
double goal_pos_thr
Definition: footstep_parameters.h:152
jsk_footstep_planner::FootstepParameters::local_move_x_num
int local_move_x_num
Definition: footstep_parameters.h:130
jsk_footstep_planner::FootstepParameters::plane_estimation_max_iterations
int plane_estimation_max_iterations
Definition: footstep_parameters.h:133
jsk_footstep_planner::FootstepParameters::local_move_y
double local_move_y
Definition: footstep_parameters.h:138
jsk_footstep_planner::FootstepParameters::transition_limit_y
double transition_limit_y
Definition: footstep_parameters.h:144
jsk_footstep_planner::FootstepParameters::local_move_theta
double local_move_theta
Definition: footstep_parameters.h:139
jsk_footstep_planner::FootstepParameters::local_move_theta_num
int local_move_theta_num
Definition: footstep_parameters.h:132
jsk_footstep_planner::FootstepParameters::local_move_theta_offset
double local_move_theta_offset
Definition: footstep_parameters.h:142
jsk_footstep_planner::FootstepParameters::transition_limit_yaw
double transition_limit_yaw
Definition: footstep_parameters.h:148
jsk_footstep_planner::FootstepParameters::support_check_vertex_neighbor_threshold
double support_check_vertex_neighbor_threshold
Definition: footstep_parameters.h:158
jsk_footstep_planner::FootstepParameters::global_transition_limit_pitch
double global_transition_limit_pitch
Definition: footstep_parameters.h:150
jsk_footstep_planner::FootstepParameters::goal_rot_thr
double goal_rot_thr
Definition: footstep_parameters.h:153
jsk_footstep_planner
Definition: ann_grid.h:50
jsk_footstep_planner::FootstepParameters::plane_estimation_min_ratio_of_inliers
double plane_estimation_min_ratio_of_inliers
Definition: footstep_parameters.h:156
jsk_footstep_planner::FootstepParameters::plane_estimation_min_inliers
int plane_estimation_min_inliers
Definition: footstep_parameters.h:134
jsk_footstep_planner::FootstepParameters::support_padding_y
double support_padding_y
Definition: footstep_parameters.h:160
jsk_footstep_planner::FootstepParameters::use_transition_limit
bool use_transition_limit
Definition: footstep_parameters.h:125
jsk_footstep_planner::FootstepParameters::support_check_y_sampling
int support_check_y_sampling
Definition: footstep_parameters.h:136
jsk_footstep_planner::FootstepParameters::plane_estimation_normal_opening_angle
double plane_estimation_normal_opening_angle
Definition: footstep_parameters.h:155
jsk_footstep_planner::FootstepParameters::local_move_x_offset
double local_move_x_offset
Definition: footstep_parameters.h:140
jsk_footstep_planner::FootstepParameters::transition_limit_z
double transition_limit_z
Definition: footstep_parameters.h:145
jsk_footstep_planner::FootstepParameters::transition_limit_roll
double transition_limit_roll
Definition: footstep_parameters.h:146
jsk_footstep_planner::FootstepParameters::support_check_x_sampling
int support_check_x_sampling
Definition: footstep_parameters.h:135
jsk_footstep_planner::FootstepParameters::global_transition_limit_roll
double global_transition_limit_roll
Definition: footstep_parameters.h:149
jsk_footstep_planner::FootstepParameters::transition_limit_x
double transition_limit_x
Definition: footstep_parameters.h:143
jsk_footstep_planner::FootstepParameters::plane_estimation_normal_distance_weight
double plane_estimation_normal_distance_weight
Definition: footstep_parameters.h:154
jsk_footstep_planner::FootstepParameters::support_padding_x
double support_padding_x
Definition: footstep_parameters.h:159
jsk_footstep_planner::FootstepParameters::local_move_x
double local_move_x
Definition: footstep_parameters.h:137
jsk_footstep_planner::FootstepParameters::skip_cropping
bool skip_cropping
Definition: footstep_parameters.h:129
jsk_footstep_planner::FootstepParameters::collision_padding
double collision_padding
Definition: footstep_parameters.h:161
jsk_footstep_planner::FootstepParameters::local_move_y_offset
double local_move_y_offset
Definition: footstep_parameters.h:141
jsk_footstep_planner::FootstepParameters::transition_limit_pitch
double transition_limit_pitch
Definition: footstep_parameters.h:147
jsk_footstep_planner::FootstepParameters::use_global_transition_limit
bool use_global_transition_limit
Definition: footstep_parameters.h:127
jsk_footstep_planner::FootstepParameters::obstacle_resolution
double obstacle_resolution
Definition: footstep_parameters.h:151
jsk_footstep_planner::FootstepParameters::FootstepParameters
FootstepParameters()
Definition: footstep_parameters.h:108
jsk_footstep_planner::FootstepParameters::plane_estimation_outlier_threshold
double plane_estimation_outlier_threshold
Definition: footstep_parameters.h:157
jsk_footstep_planner::FootstepParameters::plane_estimation_use_normal
bool plane_estimation_use_normal
Definition: footstep_parameters.h:128
jsk_footstep_planner::FootstepParameters::local_move_y_num
int local_move_y_num
Definition: footstep_parameters.h:131


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Jan 24 2024 04:05:29