lf_test.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2010, LABUST, UNIZG-FER
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the LABUST nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *
00034 *  Author: Dula Nad
00035 *  Created: 01.02.2013.
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         //Initialize
00102         labust::control::HLControl<LFControl,
00103                 labust::control::EnablePolicy,
00104                 labust::control::NoWindup,
00105                 std_msgs::Float32> controller;
00106         //Start execution.
00107         ros::spin();
00108         return 0;
00109 }
00110 
00111 
00112 


labust_uvapp
Author(s): Dula Nad
autogenerated on Fri Feb 7 2014 11:36:37