#include <sbpl_arm_planner/pr2/pr2_workspace.h>
Go to the source code of this file.
Defines | |
| #define | OFFSET fo_arm_up_arm_angle_offset |
| #define | PI 3.14159 |
Functions | |
| bool | check_joint_limits (double shlift_wrt_shpan_uvect[3], double shlift[3], vector< double > elbow_pose, double endeff_pose[3]) |
| bool | check_joint_limits_and_append_joint_angles (double pan, double shlift_wrt_shpan_uvect[3], double shlift[3], vector< double > &elbow_pose, double endeff_pose[3]) |
| void | elbow_positions_given_endeff_pose (vector< vector< double > > &list_of_accepted_points, vector< vector< double > > &list_of_rejected_points, double pan_start, double resolution, double x, double y, double z) |
| vector< vector< double > > | elbow_positions_given_endeff_pose (double pan_start, double resolution, double x, double y, double z) |
| vector< vector< double > > | elbow_positions_given_pan (double x1, double y1, double z1, double r1, double x2, double y2, double z2, double r2, double vect[3]) |
| void | grid2world (long i, long j, long k, double &x, double &y, double &z) |
| bool | position (long i, long j, long k) |
| void | separate_rejected_points (vector< vector< double > > list_of_rejected_points, vector< vector< double > > &rejected_due_to_lift, vector< vector< double > > &rejected_due_to_flex, vector< vector< double > > &rejected_due_to_roll) |
| void | world2grid (double x, double y, double z, long &i, long &j, long &k) |
Variables | |
| double | fo_arm_up_arm_angle_offset = 0.0 |
| double | grid_size_x = 1.6 |
| double | grid_size_y = 1.6 |
| double | grid_size_z = 1.4 |
| double | jnt_max [] = { 0.714, 1.396, 0.850, 0.000} |
| double | jnt_min [] = {-2.285, -0.523, -3.899, -2.299} |
| double | L_fo_arm = 0.321 |
| double | L_sh = 0.100 |
| double | L_up_arm = 0.410 |
| double | lower_corner_x = -0.6 |
| double | lower_corner_y = -1.25 |
| double | lower_corner_z = -0.05 |
| double | pan_res = 0.06981 |
| double | resolution_x = 0.02 |
| double | resolution_y = 0.02 |
| double | resolution_z = 0.02 |
| double | shoulder_pan_x = -0.050 |
| double | shoulder_pan_y = -0.188 |
| double | shoulder_pan_z = 0.743 |
| #define OFFSET fo_arm_up_arm_angle_offset |
Definition at line 29 of file pr2_workspace.cpp.
| #define PI 3.14159 |
Definition at line 30 of file pr2_workspace.cpp.
| bool check_joint_limits | ( | double | shlift_wrt_shpan_uvect[3], | |
| double | shlift[3], | |||
| vector< double > | elbow_pose, | |||
| double | endeff_pose[3] | |||
| ) |
Definition at line 213 of file pr2_workspace.cpp.
| bool check_joint_limits_and_append_joint_angles | ( | double | pan, | |
| double | shlift_wrt_shpan_uvect[3], | |||
| double | shlift[3], | |||
| vector< double > & | elbow_pose, | |||
| double | endeff_pose[3] | |||
| ) |
Definition at line 117 of file pr2_workspace.cpp.
| void elbow_positions_given_endeff_pose | ( | vector< vector< double > > & | list_of_accepted_points, | |
| vector< vector< double > > & | list_of_rejected_points, | |||
| double | pan_start, | |||
| double | resolution, | |||
| double | x, | |||
| double | y, | |||
| double | z | |||
| ) |
Definition at line 336 of file pr2_workspace.cpp.
| vector<vector<double> > elbow_positions_given_endeff_pose | ( | double | pan_start, | |
| double | resolution, | |||
| double | x, | |||
| double | y, | |||
| double | z | |||
| ) |
Definition at line 283 of file pr2_workspace.cpp.
| vector<vector<double> > elbow_positions_given_pan | ( | double | x1, | |
| double | y1, | |||
| double | z1, | |||
| double | r1, | |||
| double | x2, | |||
| double | y2, | |||
| double | z2, | |||
| double | r2, | |||
| double | vect[3] | |||
| ) |
Definition at line 55 of file pr2_workspace.cpp.
| void grid2world | ( | long | i, | |
| long | j, | |||
| long | k, | |||
| double & | x, | |||
| double & | y, | |||
| double & | z | |||
| ) |
Definition at line 33 of file pr2_workspace.cpp.
| bool position | ( | long | i, | |
| long | j, | |||
| long | k | |||
| ) |
Definition at line 424 of file pr2_workspace.cpp.
| void separate_rejected_points | ( | vector< vector< double > > | list_of_rejected_points, | |
| vector< vector< double > > & | rejected_due_to_lift, | |||
| vector< vector< double > > & | rejected_due_to_flex, | |||
| vector< vector< double > > & | rejected_due_to_roll | |||
| ) |
Definition at line 394 of file pr2_workspace.cpp.
| void world2grid | ( | double | x, | |
| double | y, | |||
| double | z, | |||
| long & | i, | |||
| long & | j, | |||
| long & | k | |||
| ) |
Definition at line 40 of file pr2_workspace.cpp.
| double fo_arm_up_arm_angle_offset = 0.0 |
Definition at line 28 of file pr2_workspace.cpp.
| double grid_size_x = 1.6 |
Definition at line 8 of file pr2_workspace.cpp.
| double grid_size_y = 1.6 |
Definition at line 9 of file pr2_workspace.cpp.
| double grid_size_z = 1.4 |
Definition at line 10 of file pr2_workspace.cpp.
| double jnt_max[] = { 0.714, 1.396, 0.850, 0.000} |
Definition at line 26 of file pr2_workspace.cpp.
| double jnt_min[] = {-2.285, -0.523, -3.899, -2.299} |
Definition at line 25 of file pr2_workspace.cpp.
| double L_fo_arm = 0.321 |
Definition at line 22 of file pr2_workspace.cpp.
| double L_sh = 0.100 |
Definition at line 23 of file pr2_workspace.cpp.
| double L_up_arm = 0.410 |
Definition at line 21 of file pr2_workspace.cpp.
| double lower_corner_x = -0.6 |
Definition at line 5 of file pr2_workspace.cpp.
| double lower_corner_y = -1.25 |
Definition at line 6 of file pr2_workspace.cpp.
| double lower_corner_z = -0.05 |
Definition at line 7 of file pr2_workspace.cpp.
| double pan_res = 0.06981 |
Definition at line 15 of file pr2_workspace.cpp.
| double resolution_x = 0.02 |
Definition at line 12 of file pr2_workspace.cpp.
| double resolution_y = 0.02 |
Definition at line 13 of file pr2_workspace.cpp.
| double resolution_z = 0.02 |
Definition at line 14 of file pr2_workspace.cpp.
| double shoulder_pan_x = -0.050 |
Definition at line 17 of file pr2_workspace.cpp.
| double shoulder_pan_y = -0.188 |
Definition at line 18 of file pr2_workspace.cpp.
| double shoulder_pan_z = 0.743 |
Definition at line 19 of file pr2_workspace.cpp.