66 boost::mutex::scoped_lock lock(
mutex_);
73 Eigen::Vector3f desired_vel = Eigen::Vector3f::Zero();
77 boost::mutex::scoped_lock lock(
mutex_);
85 geometry_msgs::Twist
cmd;
86 cmd.linear.x = desired_vel[0];
87 cmd.linear.y = desired_vel[1];
88 cmd.angular.z = desired_vel[2];
98 Eigen::Vector3f best = Eigen::Vector3f::Zero();
100 bool trajectory_found =
false;
104 Eigen::Vector3f check_vel = Eigen::Vector3f::Zero();
105 check_vel[0] = desired_vel[0] - i * dx;
106 check_vel[1] = desired_vel[1];
107 check_vel[2] = start_th;
109 check_vel[2] = start_th + j * dth;
112 Eigen::Vector3f diffs = (desired_vel - check_vel);
113 double sq_dist = diffs[0] * diffs[0] + diffs[1] * diffs[1] + diffs[2] * diffs[2];
116 if(sq_dist < best_dist){
119 trajectory_found =
true;
128 double trans_scaling_factor = 0.0;
129 double rot_scaling_factor = 0.0;
130 double scaling_factor = 0.0;
132 if(fabs(desired_vel[0]) > 0 && fabs(desired_vel[1]) > 0)
134 else if(fabs(desired_vel[0]) > 0)
136 else if(fabs(desired_vel[1]) > 0)
139 if(fabs(desired_vel[2]) > 0)
143 scaling_factor = std::min(trans_scaling_factor, rot_scaling_factor);
145 scaling_factor = trans_scaling_factor;
147 scaling_factor = rot_scaling_factor;
150 best = scaling_factor * best;
153 geometry_msgs::Twist best_cmd;
154 best_cmd.linear.x = best[0];
155 best_cmd.linear.y = best[1];
156 best_cmd.angular.z = best[2];
165 int main(
int argc,
char** argv){
166 ros::init(argc, argv,
"assisted_teleop");
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
void publish(const boost::shared_ptr< M > &message) const
double collision_trans_speed_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
double controller_frequency_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
double collision_rot_speed_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
tf::TransformListener tf_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
base_local_planner::TrajectoryPlannerROS planner_
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
boost::thread * planning_thread_
costmap_2d::Costmap2DROS costmap_ros_
int main(int argc, char **argv)
void velCB(const geometry_msgs::TwistConstPtr &vel)
geometry_msgs::Twist cmd_vel_