2010-12-26 20:59:17 -04:00
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
< html xmlns = "http://www.w3.org/1999/xhtml" >
< head >
< meta http-equiv = "Content-Type" content = "text/xhtml;charset=UTF-8" / >
< title > ArduPilot Libraries: Navigation Class Reference< / title >
< link href = "tabs.css" rel = "stylesheet" type = "text/css" / >
2010-12-26 23:23:35 -04:00
< link href = "search/search.css" rel = "stylesheet" type = "text/css" / >
< script type = "text/javaScript" src = "search/search.js" > < / script >
2010-12-26 20:59:17 -04:00
< link href = "doxygen.css" rel = "stylesheet" type = "text/css" / >
< / head >
2010-12-26 23:23:35 -04:00
< body onload = 'searchBox.OnSelectItem(0);' >
2010-12-26 20:59:17 -04:00
<!-- Generated by Doxygen 1.7.1 -->
< div class = "navigation" id = "top" >
< div class = "tabs" >
< ul class = "tablist" >
< li > < a href = "main.html" > < span > Main Page< / span > < / a > < / li >
< li > < a href = "namespaces.html" > < span > Namespaces< / span > < / a > < / li >
< li class = "current" > < a href = "annotated.html" > < span > Classes< / span > < / a > < / li >
< li > < a href = "files.html" > < span > Files< / span > < / a > < / li >
< / ul >
< / div >
< div class = "tabs2" >
< ul class = "tablist" >
< li > < a href = "annotated.html" > < span > Class List< / span > < / a > < / li >
< li > < a href = "classes.html" > < span > Class Index< / span > < / a > < / li >
< li > < a href = "hierarchy.html" > < span > Class Hierarchy< / span > < / a > < / li >
< li > < a href = "functions.html" > < span > Class Members< / span > < / a > < / li >
< / ul >
< / div >
< / div >
< div class = "header" >
< div class = "summary" >
< a href = "#pub-methods" > Public Member Functions< / a > |
< a href = "#pub-attribs" > Public Attributes< / a > < / div >
< div class = "headertitle" >
< h1 > Navigation Class Reference< / h1 > < / div >
< / div >
< div class = "contents" >
<!-- doxytag: class="Navigation" -->
< p > < code > #include < < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > > < / code > < / p >
< div class = "dynheader" >
Collaboration diagram for Navigation:< / div >
< div class = "dyncontent" >
< div class = "center" > < img src = "class_navigation__coll__graph.png" border = "0" usemap = "#_navigation_coll__map" alt = "Collaboration graph" / > < / div >
< map name = "_navigation_coll__map" id = "_navigation_coll__map" >
< area shape = "rect" id = "node2" href = "struct_waypoints_1_1_w_p.html" title = "Waypoints::WP" alt = "" coords = "5,101,117,131" / > < area shape = "rect" id = "node4" href = "class_g_p_s.html" title = "Abstract base class for GPS receiver drivers." alt = "" coords = "141,101,189,131" / > < area shape = "rect" id = "node6" href = "class_stream.html" title = "Stream" alt = "" coords = "131,5,200,35" / > < area shape = "rect" id = "node8" href = "class_waypoints.html" title = "Waypoints" alt = "" coords = "213,101,299,131" / > < / map >
< center > < span class = "legend" > [< a target = "top" href = "graph_legend.html" > legend< / a > ]< / span > < / center > < / div >
< p > < a href = "class_navigation-members.html" > List of all members.< / a > < / p >
< table class = "memberdecls" >
< tr > < td colspan = "2" > < h2 > < a name = "pub-methods" > < / a >
Public Member Functions< / h2 > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a128f871ef138c360fb2c73ffec72729f" > Navigation< / a > (< a class = "el" href = "class_g_p_s.html" > GPS< / a > *withGPS, < a class = "el" href = "class_waypoints.html" > Waypoints< / a > *withWP)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a9d2b3544acc5bf511da32c3e6888acd5" > update_gps< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a55010dc9ffe03ecba91bbfbb4e8f190c" > set_home< / a > (< a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > loc)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a222cd205c6709681875cbb4efa2657f0" > set_next_wp< / a > (< a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > loc)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a7d1a2aec8970bd7c4a6f26b4a31f69b1" > load_first_wp< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a307d267e9ce8cc9c73e52dde8f02a5ca" > load_wp_with_index< / a > (uint8_t i)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#ac1eb3234566b231e44a2a5fbc6d25ca9" > load_home< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a3cb86f630e37f5d41467a23a7a8cf831" > return_to_home_with_alt< / a > (uint32_t alt)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a99a4fd20cd5e7a0bf0fd8cfa5272e79f" > reload_wp< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a360a3f5097cf11ba28f12df55031d7b0" > load_wp_index< / a > (uint8_t i)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#ae916ccef7d89b09a972ceda58d5ef9b6" > hold_location< / a > ()< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#ad205d021d42786775c6b7d7e9d3c16f4" > set_wp< / a > (< a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > loc)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a260152de551277ff2a980e63bbb14fbc" > set_hold_course< / a > (int16_t b)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int16_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a60d4bee672c92c1e4cced76089836ebf" > get_hold_course< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#ac05da5065688d7ef70452bbc4b8f8556" > get_distance< / a > (< a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > *loc1, < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > *loc2)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#acf7075f5eedf8f47ae88b7ae04bccb39" > get_bearing< / a > (< a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > *loc1, < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > *loc2)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a3719b4db98a8fdc08599eff7e8e819af" > set_bearing_error< / a > (int32_t error)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a9aba08c1a7b668b80f2f3df8795095b6" > set_loiter_vector< / a > (int16_t v)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > void < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#ab1178280258ea8502960ffb5b4fb2815" > update_crosstrack< / a > (void)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#abda1088bf8790dbcd31687ad4daf05b1" > wrap_180< / a > (int32_t error)< / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a5ae7eb15b8aa81aeb2e2771fec018d5f" > wrap_360< / a > (int32_t angle)< / td > < / tr >
< tr > < td colspan = "2" > < h2 > < a name = "pub-attribs" > < / a >
Public Attributes< / h2 > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a327b5eb6bd65c8b1678b50d1002d95cb" > bearing< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a5131b103f30de83744a07575680ae8ec" > distance< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a5c655bff9637ea00a3dc3650cc1cf4f5" > altitude_above_home< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a820f2e9d1a143419eb8e92d76c5702b7" > total_distance< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a82c620baabad8049cc58fbe95a34890c" > bearing_error< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int32_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a63e21494db8c2022f5ff488295f2f1fe" > altitude_error< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > int16_t < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a2e0bfad230d48a39926571d5d455f139" > loiter_sum< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#acaa6eea8382dda9ba39e0dc3960d5d37" > home< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#a4f1060bf77cfc499ec5d3169c4494095" > location< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#aa4cb8fedae77c0028012bf8284bb6217" > prev_wp< / a > < / td > < / tr >
< tr > < td class = "memItemLeft" align = "right" valign = "top" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td > < td class = "memItemRight" valign = "bottom" > < a class = "el" href = "class_navigation.html#afd1dec04a84096681bf951df5edf72e0" > next_wp< / a > < / td > < / tr >
< / table >
< hr / > < a name = "_details" > < / a > < h2 > Detailed Description< / h2 >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00013" > 13< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< hr / > < h2 > Constructor & Destructor Documentation< / h2 >
< a class = "anchor" id = "a128f871ef138c360fb2c73ffec72729f" > < / a > <!-- doxytag: member="Navigation::Navigation" ref="a128f871ef138c360fb2c73ffec72729f" args="(GPS *withGPS, Waypoints *withWP)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > Navigation::Navigation < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "class_g_p_s.html" > GPS< / a > * < / td >
< td class = "paramname" > < em > withGPS< / em > , < / td >
< / tr >
< tr >
< td class = "paramkey" > < / td >
< td > < / td >
< td class = "paramtype" > < a class = "el" href = "class_waypoints.html" > Waypoints< / a > * < / td >
< td class = "paramname" > < em > withWP< / em > < / td > < td > < / td >
< / tr >
< tr >
< td > < / td >
< td > )< / td >
< td > < / td > < td > < / td > < td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00003" > 3< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< hr / > < h2 > Member Function Documentation< / h2 >
< a class = "anchor" id = "acf7075f5eedf8f47ae88b7ae04bccb39" > < / a > <!-- doxytag: member="Navigation::get_bearing" ref="acf7075f5eedf8f47ae88b7ae04bccb39" args="(Waypoints::WP *loc1, Waypoints::WP *loc2)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > long Navigation::get_bearing < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > * < / td >
< td class = "paramname" > < em > loc1< / em > , < / td >
< / tr >
< tr >
< td class = "paramkey" > < / td >
< td > < / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > * < / td >
< td class = "paramname" > < em > loc2< / em > < / td > < td > < / td >
< / tr >
< tr >
< td > < / td >
< td > )< / td >
< td > < / td > < td > < / td > < td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00235" > 235< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "ac05da5065688d7ef70452bbc4b8f8556" > < / a > <!-- doxytag: member="Navigation::get_distance" ref="ac05da5065688d7ef70452bbc4b8f8556" args="(Waypoints::WP *loc1, Waypoints::WP *loc2)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > long Navigation::get_distance < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > * < / td >
< td class = "paramname" > < em > loc1< / em > , < / td >
< / tr >
< tr >
< td class = "paramkey" > < / td >
< td > < / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > * < / td >
< td class = "paramname" > < em > loc2< / em > < / td > < td > < / td >
< / tr >
< tr >
< td > < / td >
< td > )< / td >
< td > < / td > < td > < / td > < td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00221" > 221< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a60d4bee672c92c1e4cced76089836ebf" > < / a > <!-- doxytag: member="Navigation::get_hold_course" ref="a60d4bee672c92c1e4cced76089836ebf" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int16_t Navigation::get_hold_course < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00135" > 135< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "ae916ccef7d89b09a972ceda58d5ef9b6" > < / a > <!-- doxytag: member="Navigation::hold_location" ref="ae916ccef7d89b09a972ceda58d5ef9b6" args="()" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::hold_location < / td >
< td > (< / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00079" > 79< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a7d1a2aec8970bd7c4a6f26b4a31f69b1" > < / a > <!-- doxytag: member="Navigation::load_first_wp" ref="a7d1a2aec8970bd7c4a6f26b4a31f69b1" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::load_first_wp < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00046" > 46< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "ac1eb3234566b231e44a2a5fbc6d25ca9" > < / a > <!-- doxytag: member="Navigation::load_home" ref="ac1eb3234566b231e44a2a5fbc6d25ca9" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::load_home < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00052" > 52< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a360a3f5097cf11ba28f12df55031d7b0" > < / a > <!-- doxytag: member="Navigation::load_wp_index" ref="a360a3f5097cf11ba28f12df55031d7b0" args="(uint8_t i)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::load_wp_index < / td >
< td > (< / td >
< td class = "paramtype" > uint8_t < / td >
< td class = "paramname" > < em > i< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00072" > 72< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a307d267e9ce8cc9c73e52dde8f02a5ca" > < / a > <!-- doxytag: member="Navigation::load_wp_with_index" ref="a307d267e9ce8cc9c73e52dde8f02a5ca" args="(uint8_t i)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::load_wp_with_index < / td >
< td > (< / td >
< td class = "paramtype" > uint8_t < / td >
< td class = "paramname" > < em > i< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< / div >
< / div >
< a class = "anchor" id = "a99a4fd20cd5e7a0bf0fd8cfa5272e79f" > < / a > <!-- doxytag: member="Navigation::reload_wp" ref="a99a4fd20cd5e7a0bf0fd8cfa5272e79f" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::reload_wp < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00066" > 66< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a3cb86f630e37f5d41467a23a7a8cf831" > < / a > <!-- doxytag: member="Navigation::return_to_home_with_alt" ref="a3cb86f630e37f5d41467a23a7a8cf831" args="(uint32_t alt)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::return_to_home_with_alt < / td >
< td > (< / td >
< td class = "paramtype" > uint32_t < / td >
< td class = "paramname" > < em > alt< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00058" > 58< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a3719b4db98a8fdc08599eff7e8e819af" > < / a > <!-- doxytag: member="Navigation::set_bearing_error" ref="a3719b4db98a8fdc08599eff7e8e819af" args="(int32_t error)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_bearing_error < / td >
< td > (< / td >
< td class = "paramtype" > int32_t < / td >
< td class = "paramname" > < em > error< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00175" > 175< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a260152de551277ff2a980e63bbb14fbc" > < / a > <!-- doxytag: member="Navigation::set_hold_course" ref="a260152de551277ff2a980e63bbb14fbc" args="(int16_t b)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_hold_course < / td >
< td > (< / td >
< td class = "paramtype" > int16_t < / td >
< td class = "paramname" > < em > b< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00126" > 126< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a55010dc9ffe03ecba91bbfbb4e8f190c" > < / a > <!-- doxytag: member="Navigation::set_home" ref="a55010dc9ffe03ecba91bbfbb4e8f190c" args="(Waypoints::WP loc)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_home < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td >
< td class = "paramname" > < em > loc< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00085" > 85< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a9aba08c1a7b668b80f2f3df8795095b6" > < / a > <!-- doxytag: member="Navigation::set_loiter_vector" ref="a9aba08c1a7b668b80f2f3df8795095b6" args="(int16_t v)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_loiter_vector < / td >
< td > (< / td >
< td class = "paramtype" > int16_t < / td >
< td class = "paramname" > < em > v< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00198" > 198< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a222cd205c6709681875cbb4efa2657f0" > < / a > <!-- doxytag: member="Navigation::set_next_wp" ref="a222cd205c6709681875cbb4efa2657f0" args="(Waypoints::WP loc)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_next_wp < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td >
< td class = "paramname" > < em > loc< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00093" > 93< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "ad205d021d42786775c6b7d7e9d3c16f4" > < / a > <!-- doxytag: member="Navigation::set_wp" ref="ad205d021d42786775c6b7d7e9d3c16f4" args="(Waypoints::WP loc)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::set_wp < / td >
< td > (< / td >
< td class = "paramtype" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < / td >
< td class = "paramname" > < em > loc< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< / div >
< / div >
< a class = "anchor" id = "ab1178280258ea8502960ffb5b4fb2815" > < / a > <!-- doxytag: member="Navigation::update_crosstrack" ref="ab1178280258ea8502960ffb5b4fb2815" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::update_crosstrack < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00204" > 204< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a9d2b3544acc5bf511da32c3e6888acd5" > < / a > <!-- doxytag: member="Navigation::update_gps" ref="a9d2b3544acc5bf511da32c3e6888acd5" args="(void)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > void Navigation::update_gps < / td >
< td > (< / td >
< td class = "paramtype" > void < / td >
< td class = "paramname" > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00011" > 11< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "abda1088bf8790dbcd31687ad4daf05b1" > < / a > <!-- doxytag: member="Navigation::wrap_180" ref="abda1088bf8790dbcd31687ad4daf05b1" args="(int32_t error)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t Navigation::wrap_180 < / td >
< td > (< / td >
< td class = "paramtype" > int32_t < / td >
< td class = "paramname" > < em > error< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00159" > 159< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a5ae7eb15b8aa81aeb2e2771fec018d5f" > < / a > <!-- doxytag: member="Navigation::wrap_360" ref="a5ae7eb15b8aa81aeb2e2771fec018d5f" args="(int32_t angle)" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t Navigation::wrap_360 < / td >
< td > (< / td >
< td class = "paramtype" > int32_t < / td >
< td class = "paramname" > < em > angle< / em > < / td >
< td > ) < / td >
< td > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8cpp_source.html#l00167" > 167< / a > of file < a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > .< / p >
< / div >
< / div >
< hr / > < h2 > Member Data Documentation< / h2 >
< a class = "anchor" id = "a5c655bff9637ea00a3dc3650cc1cf4f5" > < / a > <!-- doxytag: member="Navigation::altitude_above_home" ref="a5c655bff9637ea00a3dc3650cc1cf4f5" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a5c655bff9637ea00a3dc3650cc1cf4f5" > Navigation::altitude_above_home< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00045" > 45< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a63e21494db8c2022f5ff488295f2f1fe" > < / a > <!-- doxytag: member="Navigation::altitude_error" ref="a63e21494db8c2022f5ff488295f2f1fe" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a63e21494db8c2022f5ff488295f2f1fe" > Navigation::altitude_error< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00048" > 48< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a327b5eb6bd65c8b1678b50d1002d95cb" > < / a > <!-- doxytag: member="Navigation::bearing" ref="a327b5eb6bd65c8b1678b50d1002d95cb" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a327b5eb6bd65c8b1678b50d1002d95cb" > Navigation::bearing< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00043" > 43< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a82c620baabad8049cc58fbe95a34890c" > < / a > <!-- doxytag: member="Navigation::bearing_error" ref="a82c620baabad8049cc58fbe95a34890c" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a82c620baabad8049cc58fbe95a34890c" > Navigation::bearing_error< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00047" > 47< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a5131b103f30de83744a07575680ae8ec" > < / a > <!-- doxytag: member="Navigation::distance" ref="a5131b103f30de83744a07575680ae8ec" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a5131b103f30de83744a07575680ae8ec" > Navigation::distance< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00044" > 44< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "acaa6eea8382dda9ba39e0dc3960d5d37" > < / a > <!-- doxytag: member="Navigation::home" ref="acaa6eea8382dda9ba39e0dc3960d5d37" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < a class = "el" href = "class_navigation.html#acaa6eea8382dda9ba39e0dc3960d5d37" > Navigation::home< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00051" > 51< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a4f1060bf77cfc499ec5d3169c4494095" > < / a > <!-- doxytag: member="Navigation::location" ref="a4f1060bf77cfc499ec5d3169c4494095" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < a class = "el" href = "class_navigation.html#a4f1060bf77cfc499ec5d3169c4494095" > Navigation::location< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00051" > 51< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a2e0bfad230d48a39926571d5d455f139" > < / a > <!-- doxytag: member="Navigation::loiter_sum" ref="a2e0bfad230d48a39926571d5d455f139" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int16_t < a class = "el" href = "class_navigation.html#a2e0bfad230d48a39926571d5d455f139" > Navigation::loiter_sum< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00050" > 50< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "afd1dec04a84096681bf951df5edf72e0" > < / a > <!-- doxytag: member="Navigation::next_wp" ref="afd1dec04a84096681bf951df5edf72e0" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < a class = "el" href = "class_navigation.html#afd1dec04a84096681bf951df5edf72e0" > Navigation::next_wp< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00051" > 51< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "aa4cb8fedae77c0028012bf8284bb6217" > < / a > <!-- doxytag: member="Navigation::prev_wp" ref="aa4cb8fedae77c0028012bf8284bb6217" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > < a class = "el" href = "struct_waypoints_1_1_w_p.html" > Waypoints::WP< / a > < a class = "el" href = "class_navigation.html#aa4cb8fedae77c0028012bf8284bb6217" > Navigation::prev_wp< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00051" > 51< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< a class = "anchor" id = "a820f2e9d1a143419eb8e92d76c5702b7" > < / a > <!-- doxytag: member="Navigation::total_distance" ref="a820f2e9d1a143419eb8e92d76c5702b7" args="" -->
< div class = "memitem" >
< div class = "memproto" >
< table class = "memname" >
< tr >
< td class = "memname" > int32_t < a class = "el" href = "class_navigation.html#a820f2e9d1a143419eb8e92d76c5702b7" > Navigation::total_distance< / a > < / td >
< / tr >
< / table >
< / div >
< div class = "memdoc" >
< p > Definition at line < a class = "el" href = "_navigation_8h_source.html#l00046" > 46< / a > of file < a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > .< / p >
< / div >
< / div >
< hr / > The documentation for this class was generated from the following files:< ul >
< li > /home/jgoppert/Projects/ap/libraries/AP_Navigation/< a class = "el" href = "_navigation_8h_source.html" > Navigation.h< / a > < / li >
< li > /home/jgoppert/Projects/ap/libraries/AP_Navigation/< a class = "el" href = "_navigation_8cpp_source.html" > Navigation.cpp< / a > < / li >
< / ul >
< / div >
2010-12-26 23:23:35 -04:00
< hr class = "footer" / > < address class = "footer" > < small >
Generated for ArduPilot Libraries by < a href = "http://www.doxygen.org/index.html" > < img class = "footer" src = "doxygen.png" alt = "doxygen" / > < / a > < / small > < / address >
2010-12-26 20:59:17 -04:00
< / body >
< / html >