NuManual.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 <labust/control/EnablePolicy.hpp>
00039 #include <labust/control/ManControl.hpp>
00040 #include <labust/tools/MatrixLoader.hpp>
00041 #include <labust/tools/conversions.hpp>
00042 
00043 #include <auv_msgs/BodyVelocityReq.h>
00044 
00045 namespace labust
00046 {
00047         namespace control{
00049                 template <class Enable>
00050                 struct NuManual : public Enable, ConfigureAxesPolicy
00051                 {
00052                         NuManual():
00053                         nu_max(Eigen::Vector6d::Zero())
00054                         {this->init();};
00055 
00056                         void init()
00057                         {
00058                                 ros::NodeHandle nh;
00059                                 joy = nh.subscribe<sensor_msgs::Joy>("joy", 1,
00060                                                 &NuManual::onJoy,this);
00061                                 nuRef = nh.advertise<auv_msgs::BodyVelocityReq>("nuRef", 1);
00062 
00063                                 initialize_manual();
00064                         }
00065 
00066                         void onJoy(const sensor_msgs::Joy::ConstPtr& joyIn)
00067                         {
00068                                 if (!Enable::enable) return;
00069                                 auv_msgs::BodyVelocityReq::Ptr nu(new auv_msgs::BodyVelocityReq());
00070                                 Eigen::Vector6d mapped;
00071                                 mapper.remap(*joyIn, mapped);
00072 
00073                                 nu->header.stamp = ros::Time::now();
00074                                 nu->header.frame_id = "base_link";
00075                                 nu->goal.requester = "nu_manual";
00076                                 nu->disable_axis = this->disable_axis;
00077 
00078                                 mapped = nu_max.cwiseProduct(mapped);
00079                                 labust::tools::vectorToPoint(mapped, nu->twist.linear);
00080                                 labust::tools::vectorToPoint(mapped, nu->twist.angular, 3);
00081 
00082                                 nuRef.publish(nu);
00083                         }
00084 
00085                         void initialize_manual()
00086                         {
00087                                 ROS_INFO("Initializing manual nu controller...");
00088 
00089                                 ros::NodeHandle nh;
00090                                 labust::tools::getMatrixParam(nh,"nu_manual/maximum_speeds", nu_max);
00091 
00092                                 ROS_INFO("Manual nu controller initialized.");
00093                         }
00094 
00095                 private:
00096                         Eigen::Vector6d nu_max;
00097                         ros::Subscriber joy;
00098                         ros::Publisher nuRef;
00099                         JoystickMapping mapper;
00100                 };
00101         }
00102 }
00103 
00104 int main(int argc, char* argv[])
00105 {
00106         ros::init(argc,argv,"nu_manual");
00107 
00108         labust::control::NuManual<labust::control::EnableServicePolicy> controller;
00109         ros::spin();
00110 
00111         return 0;
00112 }
00113 
00114 
00115 


labust_control
Author(s): Gyula Nagy
autogenerated on Fri Aug 28 2015 11:22:42