18 #ifndef H_WHEEL_CONTROLLER_IMPL 19 #define H_WHEEL_CONTROLLER_IMPL 27 #include <geometry_msgs/Twist.h> 29 #include <boost/scoped_ptr.hpp> 30 #include <boost/weak_ptr.hpp> 31 #include <boost/thread/mutex.hpp> 34 #include <cob_base_controller_utils/WheelCommands.h> 54 controller_nh.
param(
"timeout", timeout, 1.0);
68 commands_pub_->msg_.drive_target_velocity.resize(this->wheel_states_.size());
69 commands_pub_->msg_.steer_target_velocity.resize(this->wheel_states_.size());
70 commands_pub_->msg_.steer_target_position.resize(this->wheel_states_.size());
71 commands_pub_->msg_.steer_target_error.resize(this->wheel_states_.size());
82 boost::mutex::scoped_try_lock lock(
mutex_);
90 target.updated =
true;
95 this->geom_->setTarget(target.state);
133 boost::scoped_ptr<realtime_tools::RealtimePublisher<cob_base_controller_utils::WheelCommands> >
commands_pub_;
141 if(this->isRunning()){
142 boost::mutex::scoped_lock lock(mutex_);
143 if(isnan(msg->linear.x) || isnan(msg->linear.y) || isnan(msg->angular.z)) {
144 ROS_FATAL(
"Received NaN-value in Twist message. Reset target to zero.");
bool setup(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
ros::Subscriber twist_subscriber_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
virtual void starting(const ros::Time &time)
void topicCallbackTwistCmd(const geometry_msgs::Twist::ConstPtr &msg)
boost::scoped_ptr< realtime_tools::RealtimePublisher< cob_base_controller_utils::WheelCommands > > commands_pub_
Duration & fromSec(double t)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double limitValue(double value, double limit)
virtual void stopping(const ros::Time &time)
#define ROS_ERROR_STREAM(args)
std::vector< WheelCommand > wheel_commands_
void updateCtrl(const ros::Time &time, const ros::Duration &period)
struct cob_omni_drive_controller::WheelControllerBase::Target target_