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/VirtualTarget.hpp>
00038 #include <labust/tools/MatrixLoader.hpp>
00039 #include <labust/tools/conversions.hpp>
00040
00041 #include <auv_msgs/BodyVelocityReq.h>
00042 #include <geometry_msgs/TransformStamped.h>
00043 #include <boost/bind.hpp>
00044
00045 #include <cmath>
00046 #include <vector>
00047 #include <string>
00048
00049 using labust::control::VirtualTarget;
00050
00051 VirtualTarget::VirtualTarget():
00052 nh(ros::NodeHandle()),
00053 ph(ros::NodeHandle("~")),
00054 lastEst(ros::Time::now()),
00055 timeout(0.5),
00056 Ts(0.1),
00057 safetyRadius(0.5),
00058 surge(1),
00059 flowSurgeEstimate(0),
00060 K1(0.2),
00061 K2(1),
00062 gammaARad(45),
00063 enable(false),
00064 use_flow_frame(false),
00065 listener(transBuffer)
00066 {this->onInit();}
00067
00068 void VirtualTarget::onInit()
00069 {
00070
00071 nuRef = nh.advertise<auv_msgs::BodyVelocityReq>("nuRef", 1);
00072 vtTwist = nh.advertise<geometry_msgs::TwistStamped>("virtual_target_twist", 1);
00073
00074
00075 stateHat = nh.subscribe<auv_msgs::NavSts>("stateHat", 1,
00076 &VirtualTarget::onEstimate,this);
00077 flowTwist = nh.subscribe<geometry_msgs::TwistStamped>("body_flow_frame_twist", 1,
00078 &VirtualTarget::onFlowTwist,this);
00079
00080
00081
00082
00083 windup = nh.subscribe<auv_msgs::BodyForceReq>("tauAch", 1,
00084 &VirtualTarget::onWindup,this);
00085 openLoopSurge = nh.subscribe<std_msgs::Float32>("open_loop_surge", 1,
00086 &VirtualTarget::onOpenLoopSurge,this);
00087 enableControl = nh.advertiseService("VT_enable",
00088 &VirtualTarget::onEnableControl, this);
00089
00090 nh.param("virtual_target/timeout",timeout,timeout);
00091 nh.param("virtual_target/use_flow_frame",use_flow_frame,use_flow_frame);
00092
00093
00094
00095
00096 initialize_controller();
00097
00098
00099
00100 }
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110
00111
00112
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139
00140
00141
00142
00143 bool VirtualTarget::onEnableControl(labust_uvapp::EnableControl::Request& req,
00144 labust_uvapp::EnableControl::Response& resp)
00145 {
00146 this->enable = req.enable;
00147 return true;
00148 }
00149
00150 void VirtualTarget::onOpenLoopSurge(const std_msgs::Float32::ConstPtr& surge)
00151 {
00152 this->surge = surge->data;
00153 }
00154
00155 void VirtualTarget::onFlowTwist(const geometry_msgs::TwistStamped::ConstPtr& flowtwist)
00156 {
00157 boost::mutex::scoped_lock l(dataMux);
00158 flowSurgeEstimate = flowtwist->twist.linear.x*flowtwist->twist.linear.x;
00159 flowSurgeEstimate += flowtwist->twist.linear.y*flowtwist->twist.linear.y;
00160 flowSurgeEstimate = sqrt(flowSurgeEstimate);
00161 }
00162
00163 void VirtualTarget::onEstimate(const auv_msgs::NavSts::ConstPtr& estimate)
00164 {
00165
00166 state = *estimate;
00167 lastEst = ros::Time::now();
00168 if (enable) this->step();
00169 };
00170
00171
00172
00173
00174
00175
00176
00177 void VirtualTarget::onWindup(const auv_msgs::BodyForceReq::ConstPtr& tauAch)
00178 {
00179
00180 headingController.windup = tauAch->disable_axis.yaw;
00181 };
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207 void VirtualTarget::step()
00208 {
00209 if (!enable) return;
00210
00211
00212 geometry_msgs::TransformStamped sfTransform, sfLocal, flowLocal;
00213 try
00214 {
00215 sfTransform = transBuffer.lookupTransform("serret_frenet_frame", "base_link_flow", ros::Time(0));
00216 flowLocal = transBuffer.lookupTransform("local", "base_link_flow", ros::Time(0));
00217 sfLocal = transBuffer.lookupTransform("local", "serret_frenet_frame", ros::Time(0));
00218 double gamma,gammaRabbit,flow_yaw,pitch,roll;
00219 labust::tools::eulerZYXFromQuaternion(sfTransform.transform.rotation,
00220 roll, pitch, gamma);
00221 labust::tools::eulerZYXFromQuaternion(sfLocal.transform.rotation,
00222 roll, pitch, gammaRabbit);
00223 labust::tools::eulerZYXFromQuaternion(flowLocal.transform.rotation, roll, pitch, flow_yaw);
00224
00225
00226
00227 boost::mutex::scoped_lock l(dataMux);
00228 if (!use_flow_frame || (flowSurgeEstimate < (surge/10)))
00229 {
00230 gamma = labust::math::wrapRad(state.orientation.yaw-gammaRabbit);
00231 flowSurgeEstimate = state.body_velocity.x;
00232 headingController.state = labust::math::wrapRad(state.orientation.yaw);
00233 }
00234 else
00235 {
00236 headingController.state = labust::math::wrapRad(flow_yaw);
00237 }
00238 l.unlock();
00239
00240 gamma=labust::math::wrapRad(gamma);
00241
00242 double distance(pow(sfTransform.transform.translation.y,2) + pow(sfTransform.transform.translation.x,2));
00243 double angleDiff(atan2(sfTransform.transform.translation.y, sfTransform.transform.translation.x));
00244 if (false && distance > 0.5 && fabs(angleDiff) > M_PI/2)
00245 {
00246 headingController.desired = angleDiff;
00247 }
00248 else
00249 {
00250
00251 double s1(sfTransform.transform.translation.x),y1(sfTransform.transform.translation.y);
00252
00253 geometry_msgs::TwistStamped sTwist;
00254
00255
00256 boost::mutex::scoped_lock l(dataMux);
00257 sTwist.twist.linear.x = flowSurgeEstimate*cos(gamma) + K1*s1;
00258
00259 l.unlock();
00260 vtTwist.publish(sTwist);
00261
00262 double gammaRef=-gammaARad*tanh(K2*y1);
00263
00264 headingController.desired = labust::math::wrapRad(gammaRabbit+gammaRef);
00265 }
00266
00267 float errorWrap = labust::math::wrapRad(headingController.desired - headingController.state);
00268 PIFFExtController_stepWrap(&headingController,Ts, errorWrap);
00269
00270 auv_msgs::BodyVelocityReq nu;
00271 nu.header.stamp = ros::Time::now();
00272 nu.goal.requester = "virtual_target";
00273 nu.twist.angular.z = headingController.output;
00274 nu.twist.linear.x = surge;
00275
00276 nuRef.publish(nu);
00277 }
00278 catch (tf2::TransformException& ex)
00279 {
00280 ROS_ERROR("%s",ex.what());
00281 }
00282 }
00283
00284 void VirtualTarget::start()
00285 {
00286 ros::spin();
00287 }
00288
00289 void VirtualTarget::initialize_controller()
00290 {
00291 ROS_INFO("Initializing dynamic positioning controller...");
00292
00293 double w(1);
00294 nh.param("virtual_target/heading_closed_loop_freq", w,w);
00295 nh.param("virtual_target/sampling",Ts,Ts);
00296 nh.param("virtual_target/approach_angle",gammaARad,gammaARad);
00297 nh.param("virtual_target/openLoopSurge",surge,surge);
00298 gammaARad = gammaARad*M_PI/180;
00299 Eigen::Vector2d gains(Eigen::Vector2d::Ones());
00300 labust::tools::getMatrixParam(nh,"virtual_target/outer_loop_gains", gains);
00301 K1 = gains(0);
00302 K2 = gains(1);
00303
00304 enum {Kp=0, Ki, Kd, Kt};
00305 PIDController_init(&headingController);
00306 headingController.gains[Kp] = 2*w;
00307 headingController.gains[Ki] = w*w;
00308 headingController.autoTracking = 0;
00309
00310 ROS_INFO("Line following controller initialized.");
00311 }