37 #ifndef ASSISTED_TELEOP_ASSISTED_TELEOP_H_ 38 #define ASSISTED_TELEOP_ASSISTED_TELEOP_H_ 40 #include <geometry_msgs/Twist.h> 43 #include <boost/thread.hpp> 52 void velCB(
const geometry_msgs::TwistConstPtr& vel);
double collision_trans_speed_
double controller_frequency_
double collision_rot_speed_
tf::TransformListener tf_
base_local_planner::TrajectoryPlannerROS planner_
boost::thread * planning_thread_
costmap_2d::Costmap2DROS costmap_ros_
void velCB(const geometry_msgs::TwistConstPtr &vel)
geometry_msgs::Twist cmd_vel_