Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <labust/control/HLControl.hpp>
00038 #include "HeadingControl_test.hpp"
00039 #include <labust/navigation/LFModel.hpp>
00040 #include <labust/math/NumberManipulation.hpp>
00041 #include <geometry_msgs/PointStamped.h>
00042 #include <std_msgs/Float32.h>
00043
00044 struct LFControl
00045 {
00046 LFControl():Ts(0.1),LFKp(1),T0(labust::navigation::LFModel::zeros(3)),Tt(labust::navigation::LFModel::zeros(3)){};
00047
00048 void init()
00049 {
00050 ros::NodeHandle nh;
00051 refPoint = nh.subscribe<geometry_msgs::PointStamped>("LFPoint", 1,
00052 &LFControl::onNewPoint,this);
00053
00054 initialize_controller();
00055 }
00056
00057 void onNewPoint(const geometry_msgs::PointStamped::ConstPtr& point)
00058 {
00059 using labust::navigation::LFModel;
00060 Tt(0) = point->point.x;
00061 Tt(1) = point->point.y;
00062 Tt(2) = point->point.z;
00063
00064 line.setLine(T0,Tt);
00065 };
00066
00067 void step(const auv_msgs::NavSts::ConstPtr& state, std_msgs::Float32::Ptr& headingRef)
00068 {
00069 T0(0) = state->position.north;
00070 T0(1) = state->position.east;
00071 T0(2) = state->position.depth;
00072
00073 double dh = line.calculatedH(T0(0),T0(1),T0(2));
00074 double d=sin(line.gamma())*(Tt(0)-T0(0))-cos(line.gamma())*(Tt(1)-T0(1));
00075 double z=labust::math::coerce(LFKp*dh,-0.7,0.7);
00076 std::cout<<"Distance to line:"<<d<<","<<dh<<", correction:"<<z<<","<<asin(z)<<std::endl;
00077 headingRef->data = labust::math::wrapRad(line.gamma() + asin(z));
00078 }
00079
00080 void initialize_controller()
00081 {
00082 ROS_INFO("Initializing lf-heading controller...");
00083
00084 ros::NodeHandle nh;
00085 nh.param("lf_controller/heading_LFKp", LFKp,LFKp);
00086 nh.param("heading_control/sampling",Ts,Ts);
00087
00088 ROS_INFO("Heading lf-heading controller initialized.");
00089 }
00090
00091 private:
00092 labust::navigation::LFModel::vector T0,Tt;
00093 labust::navigation::LFModel::Line line;
00094 ros::Subscriber refPoint;
00095 double Ts, LFKp;
00096 };
00097
00098 int main(int argc, char* argv[])
00099 {
00100 ros::init(argc,argv,"lf_control_test");
00101
00102 labust::control::HLControl<LFControl,
00103 labust::control::EnablePolicy,
00104 labust::control::NoWindup,
00105 std_msgs::Float32> controller;
00106
00107 ros::spin();
00108 return 0;
00109 }
00110
00111
00112