45 const static double EPS = 1e-5;
100 if(state_publish_rate_ <= 0.0)
140 ROS_ERROR(
"Caster joint \"%s\" not calibrated (namespace: %s)",
167 ROS_ERROR(
"The Base controller could not start because the casters were not calibrated. Relaunch the base controller after you see the caster calibration finish.");
173 ROS_ERROR(
"BaseController: could not configure velocity filters for casters");
183 double vel_mag =
sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
187 cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
188 cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
198 ROS_DEBUG(
"BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
200 ROS_DEBUG(
"BaseController:: clamped vel: %f", clamped_vel_mag);
201 ROS_DEBUG(
"BaseController:: vel: %f", vel_mag);
216 geometry_msgs::Twist result;
217 geometry_msgs::Twist alpha;
218 double delta(0), max_delta(0);
220 delta = end.linear.x - start.linear.x;
221 max_delta = max_rate.linear.x * dT;
222 if(fabs(delta) <= max_delta || max_delta < EPS)
225 alpha.linear.x = max_delta / fabs(delta);
227 delta = end.linear.y - start.linear.y;
228 max_delta = max_rate.linear.y * dT;
229 if(fabs(delta) <= max_delta || max_delta < EPS)
232 alpha.linear.y = max_delta / fabs(delta);
234 delta = end.angular.z - start.angular.z;
235 max_delta = max_rate.angular.z * dT;
236 if(fabs(delta) <= max_delta || max_delta < EPS)
239 alpha.angular.z = max_delta / fabs(delta);
241 double alpha_min = alpha.linear.x;
242 if(alpha.linear.y < alpha_min)
243 alpha_min = alpha.linear.y;
244 if(alpha.angular.z < alpha_min)
245 alpha_min = alpha.angular.z;
247 result.linear.x = start.linear.x + alpha_min * (end.linear.x - start.linear.x);
248 result.linear.y = start.linear.y + alpha_min * (end.linear.y - start.linear.y);
249 result.angular.z = start.angular.z + alpha_min * (end.angular.z - start.angular.z);
255 geometry_msgs::Twist cmd_vel;
257 cmd_vel.linear.x =
cmd_vel_.linear.x;
258 cmd_vel.linear.y =
cmd_vel_.linear.y;
259 cmd_vel.angular.z =
cmd_vel_.angular.z;
375 geometry_msgs::Twist result;
377 double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
378 double error_steer(0.0), error_steer_m_pi(0.0);
390 if(trans_vel < EPS && fabs(
cmd_vel_.angular.z) < EPS)
396 steer_angle_desired =
atan2(result.linear.y, result.linear.x);
402 steer_angle_desired);
405 steer_angle_desired_m_pi);
407 if(fabs(error_steer_m_pi) < fabs(error_steer))
409 error_steer = error_steer_m_pi;
410 steer_angle_desired = steer_angle_desired_m_pi;
431 geometry_msgs::Twist wheel_point_velocity;
432 geometry_msgs::Twist wheel_point_velocity_projected;
433 geometry_msgs::Twist wheel_caster_steer_component;
434 geometry_msgs::Twist caster_2d_velocity;
436 caster_2d_velocity.linear.x = 0;
437 caster_2d_velocity.linear.y = 0;
438 caster_2d_velocity.angular.z = 0;
440 double steer_angle_actual = 0;
444 caster_2d_velocity.angular.z =
base_kin_.
wheel_[
i].parent_->steer_velocity_desired_;
449 double costh =
cos(-steer_angle_actual);
450 double sinth =
sin(-steer_angle_actual);
452 wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
453 wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;
454 base_kin_.
wheel_[
i].wheel_speed_cmd_ = (wheel_point_velocity_projected.linear.x + wheel_caster_steer_component.linear.x) / (
base_kin_.
wheel_[
i].wheel_radius_);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void setJointCommands()
set the joint commands
ros::Time cmd_received_timestamp_
timestamp corresponding to when the command received by the node
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void commandCallback(const geometry_msgs::TwistConstPtr &msg)
deal with Twist commands
std::vector< control_toolbox::Pid > caster_position_pid_
The pid controllers for caster position.
geometry_msgs::Twist base_vel_msg_
callback message, used to remember where the base is commanded to go
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< Caster > caster_
vector of every caster attached to the base
double max_translational_velocity_
maximum translational velocity magnitude allowable
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState > > state_publisher_
publishes information about the caster and wheel controllers
geometry_msgs::Twist cmd_vel_t_
Input speed command vector represents the desired speed requested by the node. Note that this may dif...
geometry_msgs::Twist desired_vel_
Input speed command vector represents the desired speed requested by the node.
Pr2BaseController()
Default Constructor of the Pr2BaseController class.
double state_publish_rate_
double MAX_DT_
maximum dT used in computation of interpolated velocity command
bool new_cmd_available_
true when new command received by node
int num_wheels_
number of wheels connected to the base
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
std::vector< Wheel > wheel_
vector of every wheel attached to the base
ros::Time last_time_
time corresponding to when update was last called
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
geometry_msgs::Twist pointVel2D(const geometry_msgs::Point &pos, const geometry_msgs::Twist &vel)
Computes 2d velocity of a point at relative distance pos to another point with velocity (and rotation...
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double timeout_
timeout specifying time that the controller waits before setting the current velocity command to zero...
void publishState(const ros::Time ¤t_time)
Publish the state.
double kp_caster_steer_
local gain used for speed control of the caster (to achieve resultant position control) ...
void setCommand(const geometry_msgs::Twist &cmd_vel)
geometry_msgs::Twist interpolateCommand(const geometry_msgs::Twist &start, const geometry_msgs::Twist &end, const geometry_msgs::Twist &max_rate, const double &dT)
interpolates velocities within a given time based on maximum accelerations
geometry_msgs::Twist max_accel_
acceleration limits specified externally
pthread_mutex_t pr2_base_controller_lock_
mutex lock for setting and getting commands
static const T & clamp(const T &a, const T &b, const T &c)
geometry_msgs::Twist cmd_vel_
speed command vector used internally to represent the current commanded speed
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
~Pr2BaseController()
Destructor of the Pr2BaseController class.
ros::Subscriber cmd_sub_deprecated_
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
vector that stores the caster controllers
double state_publish_time_
Time interval between state publishing.
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &node)
Loads BaseKinematic's information from the xml description file and param server. ...
std::string name_
name of this BaseKinematics (generally associated with whatever controller is using it) ...
const std::string & getNamespace() const
void setDesiredCasterSteer()
set the desired caster steer
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
virtual bool update(const std::vector< T > &data_in, std::vector< T > &data_out)
void computeDesiredCasterSteer(const double &dT)
computes the desired caster speeds given the desired base speed
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
pr2_mechanism_model::RobotState * robot_state_
remembers everything about the state of the robot
void computeDesiredWheelSpeeds()
computes the desired wheel speeds given the desired base speed
int num_casters_
number of casters connected to the base
BaseKinematics base_kin_
class where the robot's information is computed and stored
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
geometry_msgs::Twist getCommand()
Returns the current position command.
std::vector< double > filtered_velocity_
ros::Time last_publish_time_
Time interval between state publishing.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
std::vector< boost::shared_ptr< JointVelocityController > > wheel_controller_
vector that stores the wheel controllers
def shortest_angular_distance(from_angle, to_angle)
void setDesiredWheelSpeeds()
sends the desired wheel speeds to the wheel controllers