45 const static double EPS = 1e-5;
101 if(state_publish_rate_ <= 0.0)
141 ROS_ERROR(
"Caster joint \"%s\" not calibrated (namespace: %s)",
169 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.");
175 ROS_ERROR(
"BaseController: could not configure velocity filters for casters");
179 ROS_ERROR(
"BaseController: could not configure velocity filters for wheels");
190 double vel_mag =
sqrt(cmd_vel.linear.x * cmd_vel.linear.x + cmd_vel.linear.y * cmd_vel.linear.y);
194 cmd_vel_t_.linear.x = cmd_vel.linear.x * clamped_vel_mag / vel_mag;
195 cmd_vel_t_.linear.y = cmd_vel.linear.y * clamped_vel_mag / vel_mag;
205 ROS_DEBUG(
"BaseController:: command received: %f %f %f",cmd_vel.linear.x,cmd_vel.linear.y,cmd_vel.angular.z);
207 ROS_DEBUG(
"BaseController:: clamped vel: %f", clamped_vel_mag);
208 ROS_DEBUG(
"BaseController:: vel: %f", vel_mag);
223 geometry_msgs::Twist result;
224 geometry_msgs::Twist alpha;
225 double delta(0), max_delta(0);
227 delta = end.linear.x - start.linear.x;
228 max_delta = max_rate.linear.x * dT;
229 if(fabs(delta) <= max_delta || max_delta < EPS)
232 alpha.linear.x = max_delta / fabs(delta);
234 delta = end.linear.y - start.linear.y;
235 max_delta = max_rate.linear.y * dT;
236 if(fabs(delta) <= max_delta || max_delta < EPS)
239 alpha.linear.y = max_delta / fabs(delta);
241 delta = end.angular.z - start.angular.z;
242 max_delta = max_rate.angular.z * dT;
243 if(fabs(delta) <= max_delta || max_delta < EPS)
246 alpha.angular.z = max_delta / fabs(delta);
248 double alpha_min = alpha.linear.x;
249 if(alpha.linear.y < alpha_min)
250 alpha_min = alpha.linear.y;
251 if(alpha.angular.z < alpha_min)
252 alpha_min = alpha.angular.z;
254 result.linear.x = start.linear.x + alpha_min * (end.linear.x - start.linear.x);
255 result.linear.y = start.linear.y + alpha_min * (end.linear.y - start.linear.y);
256 result.angular.z = start.angular.z + alpha_min * (end.angular.z - start.angular.z);
262 geometry_msgs::Twist cmd_vel;
264 cmd_vel.linear.x =
cmd_vel_.linear.x;
265 cmd_vel.linear.y =
cmd_vel_.linear.y;
266 cmd_vel.angular.z =
cmd_vel_.angular.z;
383 geometry_msgs::Twist result;
385 double steer_angle_desired(0.0), steer_angle_desired_m_pi(0.0);
386 double error_steer(0.0), error_steer_m_pi(0.0);
398 if(trans_vel < EPS && fabs(
cmd_vel_.angular.z) < EPS)
404 steer_angle_desired =
atan2(result.linear.y, result.linear.x);
410 steer_angle_desired);
413 steer_angle_desired_m_pi);
415 if(fabs(error_steer_m_pi) < fabs(error_steer))
417 error_steer = error_steer_m_pi;
418 steer_angle_desired = steer_angle_desired_m_pi;
439 geometry_msgs::Twist wheel_point_velocity;
440 geometry_msgs::Twist wheel_point_velocity_projected;
441 geometry_msgs::Twist wheel_caster_steer_component;
442 geometry_msgs::Twist caster_2d_velocity;
444 caster_2d_velocity.linear.x = 0;
445 caster_2d_velocity.linear.y = 0;
446 caster_2d_velocity.angular.z = 0;
454 double steer_angle_actual = 0;
464 double costh =
cos(-steer_angle_actual);
465 double sinth =
sin(-steer_angle_actual);
467 wheel_point_velocity_projected.linear.x = costh * wheel_point_velocity.linear.x - sinth * wheel_point_velocity.linear.y;
468 wheel_point_velocity_projected.linear.y = sinth * wheel_point_velocity.linear.x + costh * wheel_point_velocity.linear.y;
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
double max_rotational_velocity_
maximum rotational velocity magnitude allowable
std::vector< control_toolbox::Pid > wheel_pid_controllers_
The pid controllers for caster position.
void setDesiredCasterSteer()
set the desired caster steer
void computeJointCommands(const double &dT)
computes the desired caster steers and wheel speeds
double max_translational_velocity_
maximum translational velocity magnitude allowable
geometry_msgs::Twist base_vel_msg_
callback message, used to remember where the base is commanded to go
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
geometry_msgs::Twist cmd_vel_t_
Input speed command vector represents the desired speed requested by the node. Note that this may dif...
ros::Subscriber cmd_sub_deprecated_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
pthread_mutex_t pr2_base_controller_lock_
mutex lock for setting and getting commands
BaseKinematics base_kinematics_
class where the robot's information is computed and stored
std::vector< Caster > caster_
vector of every caster attached to the base
void setCommand(const geometry_msgs::Twist &cmd_vel)
void computeDesiredWheelSpeeds(const double &dT)
computes the desired wheel speeds given the desired base speed
~Pr2BaseController2()
Destructor of the Pr2BaseController2 class.
double kp_caster_steer_
local gain used for speed control of the caster (to achieve resultant position control) ...
double MAX_DT_
maximum dT used in computation of interpolated velocity command
void commandCallback(const geometry_msgs::TwistConstPtr &msg)
deal with Twist commands
int num_wheels_
number of wheels connected to the base
std::vector< double > filtered_velocity_
std::vector< Wheel > wheel_
vector of every wheel attached to the base
double timeout_
timeout specifying time that the controller waits before setting the current velocity command to zero...
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
void update()
(a) Updates commands to caster and wheels. Called every timestep in realtime
ROSLIB_DECL std::string command(const std::string &cmd)
geometry_msgs::Twist max_accel_
acceleration limits specified externally
filters::MultiChannelTransferFunctionFilter< double > caster_vel_filter_
std::vector< double > filtered_wheel_velocity_
void setJointCommands()
set the joint commands
geometry_msgs::Twist getCommand()
Returns the current position command.
void updateJointControllers()
tells the wheel and caster controllers to update their speeds
static const T & clamp(const T &a, const T &b, const T &c)
geometry_msgs::Twist desired_vel_
Input speed command vector represents the desired speed requested by the node.
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
std::vector< control_toolbox::Pid > caster_position_pid_
The pid controllers for caster position.
std::vector< boost::shared_ptr< JointVelocityController > > caster_controller_
vector that stores the caster controllers
filters::MultiChannelTransferFunctionFilter< double > wheel_vel_filter_
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
Pr2BaseController2()
Default Constructor of the Pr2BaseController2 class.
ros::Time last_time_
time corresponding to when update was last called
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
void computeDesiredCasterSteer(const double &dT)
computes the desired caster speeds given the desired base speed
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)
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
int num_casters_
number of casters connected to the base
void computeWheelPositions()
Computes 2d postion of every wheel relative to the center of the base.
ros::Time last_publish_time_
Time interval between state publishing.
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_mechanism_controllers::BaseControllerState2 > > state_publisher_
publishes information about the caster and wheel controllers
geometry_msgs::Twist cmd_vel_
speed command vector used internally to represent the current commanded speed
double state_publish_rate_
def shortest_angular_distance(from_angle, to_angle)
void setDesiredWheelSpeeds()
sends the desired wheel speeds to the wheel controllers
ros::Time cmd_received_timestamp_
timestamp corresponding to when the command received by the node
void publishState(const ros::Time ¤t_time)
Publish the state.
bool new_cmd_available_
true when new command received by node
double state_publish_time_
Time interval between state publishing.