1 #ifndef __CONTROLLER_TEMPLATE__ 2 #define __CONTROLLER_TEMPLATE__ 7 #include <sensor_msgs/JointState.h> 33 const sensor_msgs::JointState ¤t_state,
54 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
67 const sensor_msgs::JointState ¤t_state,
const ros::Duration &dt);
77 virtual sensor_msgs::JointState controlAlgorithm(
78 const sensor_msgs::JointState ¤t_state,
92 virtual void resetController() = 0;
103 sensor_msgs::JointState lastState(
const sensor_msgs::JointState ¤t);
114 void startActionlib();
119 virtual bool goalCB();
124 virtual void preemptCB();
138 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
142 : action_name_(action_name), nh_(nh)
148 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
151 ActionClass, ActionGoal, ActionFeedback,
164 << MAX_DT <<
" seconds, aborting");
184 for (
unsigned int i = 0; i < ret.name.size(); i++)
186 if (!std::isfinite(ret.position[i]) || !std::isfinite(ret.velocity[i]))
196 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
209 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
223 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
237 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
240 ActionClass, ActionGoal, ActionFeedback,
243 if (current.position.size() == 0)
245 ROS_WARN(
"lastState got invalid state");
252 for (
unsigned long i = 0; i <
last_state_.velocity.size(); i++)
263 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
280 std::string package_name, path, topic;
284 if (
nh_.
getParam(
"record_bag/package", package_name))
287 bag_manager_ = std::make_shared<BagManager>(path, topic);
291 bag_manager_ = std::make_shared<BagManager>(path, topic);
296 "No record_bag/package or record_bag/path parameters detected! No " 297 "bag will be recorded");
305 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
315 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
322 template <
class ActionClass,
class ActionGoal,
class ActionFeedback,
341 ROS_INFO(
"%s initialized successfully!", action_name_.c_str());
std::string resolveName(const std::string &name, bool remap=true) const
ROSLIB_DECL std::string getPath(const std::string &package_name)
bool getParam(const std::string &key, std::string &s) const
bool hasParam(const std::string &key) const
#define ROS_ERROR_STREAM(args)
#define ROS_DEBUG_THROTTLE(period,...)