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 <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 private_nh.param("translational_collision_speed", collision_trans_speed_, 0.0);
00047 private_nh.param("rotational_collision__speed", collision_rot_speed_, 0.0);
00048 planner_.initialize("planner", &tf_, &costmap_ros_);
00049
00050 ros::NodeHandle n;
00051 pub_ = n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00052 sub_ = n.subscribe("teleop_cmd_vel", 10, &AssistedTeleop::velCB, this);
00053 cmd_vel_.linear.x = 0.0;
00054 cmd_vel_.linear.y = 0.0;
00055 cmd_vel_.linear.z = 0.0;
00056
00057 planning_thread_ = new boost::thread(boost::bind(&AssistedTeleop::controlLoop, this));
00058 }
00059
00060 AssistedTeleop::~AssistedTeleop(){
00061 planning_thread_->join();
00062 delete planning_thread_;
00063 }
00064
00065 void AssistedTeleop::velCB(const geometry_msgs::TwistConstPtr& vel){
00066 boost::mutex::scoped_lock lock(mutex_);
00067 cmd_vel_ = *vel;
00068 }
00069
00070 void AssistedTeleop::controlLoop(){
00071 ros::Rate r(controller_frequency_);
00072 while(ros::ok()){
00073 Eigen::Vector3f desired_vel = Eigen::Vector3f::Zero();
00074
00075
00076 {
00077 boost::mutex::scoped_lock lock(mutex_);
00078 desired_vel[0] = cmd_vel_.linear.x;
00079 desired_vel[1] = cmd_vel_.linear.y;
00080 desired_vel[2] = cmd_vel_.angular.z;
00081 }
00082
00083
00084 if(planner_.checkTrajectory(desired_vel[0], desired_vel[1], desired_vel[2], true)){
00085 geometry_msgs::Twist cmd;
00086 cmd.linear.x = desired_vel[0];
00087 cmd.linear.y = desired_vel[1];
00088 cmd.angular.z = desired_vel[2];
00089 pub_.publish(cmd);
00090 r.sleep();
00091 continue;
00092 }
00093
00094 double dth = (theta_range_) / double(num_th_samples_);
00095 double dx = desired_vel[0] / double(num_x_samples_);
00096 double start_th = desired_vel[2] - theta_range_ / 2.0 ;
00097
00098 Eigen::Vector3f best = Eigen::Vector3f::Zero();
00099 double best_dist = DBL_MAX;
00100 bool trajectory_found = false;
00101
00102
00103 for(int i = 0; i < num_x_samples_; ++i){
00104 Eigen::Vector3f check_vel = Eigen::Vector3f::Zero();
00105 check_vel[0] = desired_vel[0] - i * dx;
00106 check_vel[1] = desired_vel[1];
00107 check_vel[2] = start_th;
00108 for(int j = 0; j < num_th_samples_; ++j){
00109 check_vel[2] = start_th + j * dth;
00110 if(planner_.checkTrajectory(check_vel[0], check_vel[1], check_vel[2], false)){
00111
00112 Eigen::Vector3f diffs = (desired_vel - check_vel);
00113 double sq_dist = diffs[0] * diffs[0] + diffs[1] * diffs[1] + diffs[2] * diffs[2];
00114
00115
00116 if(sq_dist < best_dist){
00117 best = check_vel;
00118 best_dist = sq_dist;
00119 trajectory_found = true;
00120 }
00121 }
00122 }
00123 }
00124
00125
00126
00127 if(!trajectory_found && (collision_trans_speed_ > 0.0 || collision_rot_speed_ > 0.0)){
00128 double trans_scaling_factor = 0.0;
00129 double rot_scaling_factor = 0.0;
00130 double scaling_factor = 0.0;
00131
00132 if(fabs(desired_vel[0]) > 0 && fabs(desired_vel[1]) > 0)
00133 trans_scaling_factor = std::min(collision_trans_speed_ / fabs(desired_vel[0]), collision_trans_speed_ / fabs(desired_vel[1]));
00134 else if(fabs(desired_vel[0]) > 0)
00135 trans_scaling_factor = collision_trans_speed_ / (fabs(desired_vel[0]));
00136 else if(fabs(desired_vel[1]) > 0)
00137 trans_scaling_factor = collision_trans_speed_ / (fabs(desired_vel[1]));
00138
00139 if(fabs(desired_vel[2]) > 0)
00140 rot_scaling_factor = collision_rot_speed_ / (fabs(desired_vel[2]));
00141
00142 if(collision_trans_speed_ > 0.0 && collision_rot_speed_ > 0.0)
00143 scaling_factor = std::min(trans_scaling_factor, rot_scaling_factor);
00144 else if(collision_trans_speed_ > 0.0)
00145 scaling_factor = trans_scaling_factor;
00146 else if(collision_rot_speed_ > 0.0)
00147 scaling_factor = rot_scaling_factor;
00148
00149
00150 best = scaling_factor * best;
00151 }
00152
00153 geometry_msgs::Twist best_cmd;
00154 best_cmd.linear.x = best[0];
00155 best_cmd.linear.y = best[1];
00156 best_cmd.angular.z = best[2];
00157 pub_.publish(best_cmd);
00158
00159 r.sleep();
00160 }
00161 }
00162 };
00163
00164
00165 int main(int argc, char** argv){
00166 ros::init(argc, argv, "assisted_teleop");
00167 assisted_teleop::AssistedTeleop at;
00168 ros::spin();
00169 return 0;
00170 }