18 #ifndef H_GEOM_CONTROLLER_IMPL
19 #define H_GEOM_CONTROLLER_IMPL
23 #include <boost/scoped_ptr.hpp>
33 boost::scoped_ptr<Controller>
geom_;
46 bool setup(
const std::vector<typename Controller::WheelParams> &wheel_params){
47 if (wheel_params.size() < 3){
48 ROS_ERROR(
"At least three wheel are needed.");
52 geom_.reset(
new Controller(wheel_params));
64 std::vector<typename Controller::WheelParams> wheel_params;
66 return init(hw, wheel_params);
69 if(!this->
setup(wheel_params))
return false;
71 for (
unsigned i=0; i<wheel_params.size(); i++){
72 this->
steer_joints_.push_back(hw->getHandle(wheel_params[i].geom.steer_name));
73 this->
drive_joints_.push_back(hw->getHandle(wheel_params[i].geom.drive_name));
76 catch(
const std::exception &e){