Public Member Functions |
| void | add_robot_wayPoints () |
| void | add_separatrix_points_toRobot (Trajectory *target_traj) |
| void | add_verts_to_vertTimeList () |
| void | cal_all_eigenvecs_quad () |
| void | cal_eigen_vector_sym (icMatrix2x2 m, icVector2 ev[2]) |
| void | cal_eigenvecs_onevert_quad (int ver) |
| void | cal_inverse_transform () |
| void | cal_sep_infoGain () |
| void | cal_separatrix_vec () |
| void | cal_tensorvals_quad () |
| void | cal_TF_at_inbetween_slice_keyframe_interp (double ratio, int start, int end) |
| void | cal_TF_at_slice_keyframe_interp (int which_slice) |
| void | cancelPath () |
| bool | check_bypass_trisector () |
| bool | check_line_insect_obstacle () |
| bool | check_reach_trisector () |
| bool | check_reach_wedge () |
| void | compute_a_alongx_degptlocate (double &a, icVector2 v0, icVector2 v1, icVector2 v2, icVector2 v3, icVector2 &v0v1, icVector2 &v2v3) |
| void | compute_degpts_pos_tranvec_quad () |
| void | compute_onedegpt_pos_tranvec_quad (int cellid, double &x, double &y) |
| void | compute_separatrixVec_degpt_quad (int degpt_index) |
| void | con_linear_Sys_spatioTemp (Vec_DP &tsa, Vec_INT &tija, Mat_DP &bound_v) |
| void | copy_from_keyframe (int keyframelistPos) |
| void | count_nonconstrained_verts () |
| void | create_paraThread () |
| void | cut_robot_path () |
| void | display_bresenham_line () |
| void | display_degenerate_pts (GLenum mode) |
| void | display_design_grid () |
| void | display_major_tenlines (GLenum mode) |
| void | display_separatrices (GLenum mode) |
| void | display_tenRegElem (GLenum mode) |
| void | display_trisectorVec (GLenum mode) |
| void | display_valid_degenerate_pts (GLenum mode) |
| void | display_valid_trisectors (GLenum mode) |
| void | draw_hollow_circle_size (double cx, double cy, double R) |
| void | draw_map_contour () |
| int | DrawGLScene (GLenum mode) |
| void | drawSolidCircle_size (double cx, double cy, double R) |
| void | drawSolidRect_size (double cx, double cy, double R) |
| void | ensure_robot_safety () |
| void | filterDegpts () |
| std::set< int > | find_connect_degpts (int target_tri_index) |
| void | frontier_point_callback (const std_msgs::Float64MultiArray &msg) |
| void | gen_major_path () |
| void | gen_separatrix () |
| void | get_laplace_TVTF (int which_slice) |
| void | get_obstacles_contour () |
| unsigned char | get_region_id (double x, double y) |
| void | get_tensor (double x, double y, double t[4]) |
| void | goTri_callback (const std_msgs::String &msg) |
| void | gridMap_callback (const nav_msgs::OccupancyGrid &msg) |
| void | init_degpts () |
| void | init_keyframeList (int size=2) |
| void | init_majorPath () |
| void | init_regular_ten_designelems () |
| void | init_separatrices () |
| void | init_ten_designelems () |
| void | init_vertTimeList () |
| int | InitGL () |
| bool | insertLinks (int i, int j) |
| void | Laplace_relax_timeDep () |
| void | listen_to_robot_loc () |
| void | locat_point_inMap (double pos[2], cv::Point2i &mapLoc) |
| void | locate_degpts_cells_tranvec_quad (void) |
| void | major_vis_quad () |
| void | make_tens_Patterns (void) |
| void | makePatterns (void) |
| void | normalized_tensorfield_quad () |
| void | parallel_cal_tensorvals_quad (int &x1, int &x2) |
| void | parallel_update_tensorField () |
| void | play_all_frames () |
| void | publish_image () |
| void | render_alpha_map_quad () |
| void | render_ibfv_tens_quad (bool x_y) |
| void | render_majorfield_quad () |
| void | render_tensor_blend () |
| void | render_tensor_final () |
| void | reset_major_path () |
| void | reset_regular_and_degenrateElem () |
| void | reset_separatrices () |
| std::map< pair< int,int >, float > | search_degpts_mst (std::set< int > connect_degpts, int target_tri_index) |
| Trajectory * | select_a_branch (std::map< pair< int, int >, float > cur_mst, int target_tri_index) |
| void | select_target_trisector_branch_move () |
| void | set_constraints_keyframes () |
| void | set_cur_as_keyframe (int frameID) |
| void | set_obstacles () |
| void | set_robot_loc (double x, double y) |
| void | set_ten_regBasis (double x, double y, int type) |
| void | set_ten_regDir (double x, double y) |
| void | set_ten_regDir (double x, double y, icVector2 &vec) |
| void | setRegularElems () |
| void | split_tensorField (int i, int threadNum, int &x1, int &x2) |
| void | tensor_init_tex () |
| | TfCore (ros::NodeHandle private_nh_=ros::NodeHandle("~")) |
| void | TfCoreInit () |
| void | transform_fun () |
| void | update_cur_TF_keyframe () |
| void | update_tensor_field () |
| int | without_anti_aliasing (GLenum mode) |
| | ~TfCore () |
Public Attributes |
| int | alpha |
| std::string | baseFrameId |
| std::vector< Location > | bresenham_line_points |
std::vector< std::vector
< icVector2 > > | constraints_vecs |
std::vector< std::vector
< cv::Point > > | contours |
std::vector< std::vector
< cv::Point2f > > | contours2Field |
std::vector< std::vector
< cv::Point2f > > | contoursInWorld |
| int | curMaxNumTenDesignElems |
| int | curMaxNumTenRegElems |
| int | curSliceID |
| int * | degenerate_tris |
| DegeneratePt * | degpts |
| std::set< pair< int, int > > | degptsLinks |
| std::vector< vector< int > > | degptsPathsInfoGain |
| nav_msgs::OccupancyGrid | dirMap |
std::vector< std::vector
< cv::Point2f > > | dirMap2Field |
std::vector< std::vector
< cv::Point2f > > | dirMapInWorld |
| float | dmax |
| bool | enRelaxKeyframeOn |
| ros::Subscriber | finishGoTri |
| ros::Subscriber | first_point_sub |
| std_msgs::Float64MultiArray | frontierPoints |
| ros::Subscriber | frontierPoints_sub |
| ros::ServiceClient | goTriExecuteclient |
| ros::Subscriber | gridmap_sub |
| std::string | gridMapTopicName |
| bool | ifCancelPath |
| bool | ifFinish_goTri |
| int | iframe |
| bool | ifReachTrisector |
| Vec_INT * | ija_p |
| int | interFrameNum |
| float | interFrameTime |
| int | InterpScheme |
| float | inverse_tran [16] |
| bool | isReceiveNewMap |
| KeyFrameList * | keyframes |
| float | leftBottom [2] |
| tf::TransformListener | listener |
| icVector2 | m_globalDirect |
| image_transport::ImageTransport | m_it |
| std::vector< ParaThread * > | m_myThreads |
| icVector2 | m_robotDirect |
| GLubyte | major_alpha_map [NPIX][NPIX][3] |
| int | major_iframe |
| EvenStreamlinePlace * | major_path |
| GLubyte | major_temp [NPIX][NPIX][4] |
| GLubyte | major_tex [NPIX][NPIX][3] |
| GLubyte | major_tex1 [NPIX][NPIX][3] |
| GLubyte | major_tex2 [NPIX][NPIX][3] |
| int | MaxNumDegeneratePts |
| GLubyte | minor_alpha_map [NPIX][NPIX][3] |
| GLubyte | minor_temp [NPIX][NPIX][4] |
| GLubyte | minor_tex [NPIX][NPIX][3] |
| GLubyte | minor_tex1 [NPIX][NPIX][3] |
| GLubyte | minor_tex2 [NPIX][NPIX][3] |
| int | ndegenerate_tris |
| int | ndegpts |
| ros::NodeHandle | nh_ |
| int | Npat |
| int | nten_regelems |
| int | ntenelems |
| int | NUM_Slices |
| icVector2 | outside_push |
| ros::ServiceClient | pathCancelClient |
| ros::ServiceClient | pathCutClient |
| ros::ServiceClient | pathExecuteClient |
| QuadMesh * | quadmesh |
| double | realWorld_to_field_offset_x |
| double | realWorld_to_field_offset_y |
| double | realWorld_to_field_scale |
| bool | recoverMode |
| bool | reGenPath |
| ros::ServiceClient | reqCalDegptPathsInfoClient |
| unsigned char * | rgb_im |
| image_transport::Publisher | rgb_pub |
| std::string | rgbTopicName |
| float | rightTop [2] |
| Seed * | robot_loc |
| float | robot_world_pos [2] |
| float | robotInitialPos_x |
| float | robotInitialPos_y |
| Vec_DP * | sa_p |
| float | safeDistance |
| ros::Publisher | safetyWayPointNum_pub |
| int | selected_target_tri |
| EvenStreamlinePlace * | separatrices |
| bool | showGridOn |
| bool | showIBFVOn |
| bool | showMajorTenLine |
| bool | showRegularElemOn |
| bool | showSingularitiesOn |
| ros::Subscriber | target_sub |
| int | targetTrisectorIndex |
| Degenerate_Design * | ten_designelems |
| double | ten_dmax |
| TenRegularElem * | ten_regularelems |
| double | ten_tmax |
| GLuint | tentextnames [16] |
| float | tmax |
| double | trans_x |
| double | trans_y |
| std::vector< DegeneratePt > | validDegpts |
| std::vector< DegeneratePt > | validTriDegpts |
| icVector2 * | vecsTime |
| VertTimeList * | vertTimeList |
| std::string | worldFrameId |
| double | zoom_factor |
Definition at line 39 of file TfCore.h.