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 <nxt_assisted_teleop/assisted_teleop.h>
00038
00039 namespace assisted_teleop {
00040 AssistedTeleop::AssistedTeleop() : costmap_ros_("costmap", tf_), planning_thread_(NULL){
00041 ros::NodeHandle private_nh("~");
00042 private_nh.param("controller_frequency", controller_frequency_, 10.0);
00043 private_nh.param("num_th_samples", num_th_samples_, 20);
00044 private_nh.param("num_x_samples", num_x_samples_, 10);
00045 private_nh.param("theta_range", theta_range_, 0.7);
00046 planner_.initialize("planner", &tf_, &costmap_ros_);
00047
00048 ros::NodeHandle n;
00049 sub_ = n.subscribe("teleop_cmd_vel", 10, &AssistedTeleop::velCB, this);
00050 pub_ = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00051 cmd_vel_.linear.x = 0.0;
00052 cmd_vel_.linear.y = 0.0;
00053 cmd_vel_.linear.z = 0.0;
00054
00055 planning_thread_ = new boost::thread(boost::bind(&AssistedTeleop::controlLoop, this));
00056 }
00057
00058 AssistedTeleop::~AssistedTeleop(){
00059 planning_thread_->join();
00060 delete planning_thread_;
00061 }
00062
00063 void AssistedTeleop::velCB(const geometry_msgs::TwistConstPtr& vel){
00064 boost::mutex::scoped_lock lock(mutex_);
00065 cmd_vel_ = *vel;
00066 }
00067
00068 void AssistedTeleop::controlLoop(){
00069 ros::Rate r(controller_frequency_);
00070 while(ros::ok()){
00071 Eigen::Vector3f desired_vel = Eigen::Vector3f::Zero();
00072
00073
00074 {
00075 boost::mutex::scoped_lock lock(mutex_);
00076 desired_vel[0] = cmd_vel_.linear.x;
00077 desired_vel[1] = cmd_vel_.linear.y;
00078 desired_vel[2] = cmd_vel_.angular.z;
00079 }
00080
00081
00082 if(planner_.checkTrajectory(desired_vel[0], desired_vel[1], desired_vel[2], true)){
00083 geometry_msgs::Twist cmd;
00084 cmd.linear.x = desired_vel[0];
00085 cmd.linear.y = desired_vel[1];
00086 cmd.angular.z = desired_vel[2];
00087 pub_.publish(cmd);
00088 r.sleep();
00089 continue;
00090 }
00091
00092 double dth = (theta_range_) / double(num_th_samples_);
00093 double dx = desired_vel[0] / double(num_x_samples_);
00094 double start_th = desired_vel[2] - theta_range_ / 2.0 ;
00095
00096 Eigen::Vector3f best = Eigen::Vector3f::Zero();
00097 double best_dist = DBL_MAX;
00098
00099
00100 for(int i = 0; i < num_x_samples_; ++i){
00101 Eigen::Vector3f check_vel = Eigen::Vector3f::Zero();
00102 check_vel[0] = desired_vel[0] - i * dx;
00103 check_vel[1] = desired_vel[1];
00104 check_vel[2] = start_th;
00105 for(int j = 0; j < num_th_samples_; ++j){
00106 check_vel[2] = start_th + j * dth;
00107 if(planner_.checkTrajectory(check_vel[0], check_vel[1], check_vel[2], false)){
00108
00109 Eigen::Vector3f diffs = (desired_vel - check_vel);
00110 double sq_dist = diffs[0] * diffs[0] + diffs[1] * diffs[1] + diffs[2] * diffs[2];
00111
00112
00113 if(sq_dist < best_dist){
00114 best = check_vel;
00115 best_dist = sq_dist;
00116 }
00117 }
00118 }
00119 }
00120
00121 geometry_msgs::Twist best_cmd;
00122 best_cmd.linear.x = best[0];
00123 best_cmd.linear.y = best[1];
00124 best_cmd.angular.z = best[2];
00125 pub_.publish(best_cmd);
00126
00127 r.sleep();
00128 }
00129 }
00130 };
00131
00132
00133 int main(int argc, char** argv){
00134 ros::init(argc, argv, "assisted_teleop");
00135 assisted_teleop::AssistedTeleop at;
00136 ros::spin();
00137 return 0;
00138 }