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 <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