control_multi_plugin.cpp
Go to the documentation of this file.
1 #include "GeomController.h"
2 #include "WheelControllerBase.h"
5 
7 {
8 
9 class GeomMultiController : public GeomControllerBase< hardware_interface::JointHandle, UndercarriageDirectCtrl>,
10  public controller_interface::MultiInterfaceController<hardware_interface::VelocityJointInterface, hardware_interface::PositionJointInterface> {
11 };
12 
13 class WheelMultiController : public WheelControllerBase< GeomMultiController >
14 {
15 public:
16  virtual bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle& controller_nh){
17  std::vector<UndercarriageDirectCtrl::WheelParams> wheel_params;
18  if(!parseWheelParams(wheel_params, controller_nh)) return false;
19  if(!GeomControllerBase::setup(wheel_params)) return false;
20 
23 
24  try{
25  for (unsigned i=0; i<wheel_params.size(); i++){
26  this->steer_joints_.push_back(p->getHandle(wheel_params[i].geom.steer_name));
27  this->drive_joints_.push_back(v->getHandle(wheel_params[i].geom.drive_name));
28  }
29  }
30  catch(const std::exception &e){
31  ROS_ERROR_STREAM("Error while attaching handles: " << e.what());
32  return false;
33  }
34  return this->setup(root_nh,controller_nh);
35  }
36  virtual void update(const ros::Time& time, const ros::Duration& period){
37 
38  updateState();
39 
40  updateCtrl(time, period);
41 
42  for (unsigned i=0; i<wheel_commands_.size(); i++){
43  steer_joints_[i].setCommand(wheel_commands_[i].dAngGearSteerRad);
44  drive_joints_[i].setCommand(wheel_commands_[i].dVelGearDriveRadS);
45  }
46 
47  }
48 };
49 
50 }
51 
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
cob_omni_drive_controller::parseWheelParams
bool parseWheelParams(std::vector< UndercarriageGeom::WheelParams > &params, const ros::NodeHandle &nh, bool read_urdf=true)
Definition: param_parser.cpp:270
cob_omni_drive_controller::GeomControllerBase< hardware_interface::JointHandle, UndercarriageDirectCtrl >::drive_joints_
std::vector< hardware_interface::JointHandle > drive_joints_
Definition: GeomController.h:31
cob_omni_drive_controller::GeomControllerBase< hardware_interface::JointHandle, UndercarriageDirectCtrl >::updateState
void updateState()
Definition: GeomController.h:36
WheelControllerBase.h
HardwareResourceManager< JointHandle, ClaimResources >::getHandle
JointHandle getHandle(const std::string &name)
hardware_interface::InterfaceManager::get
T * get()
cob_omni_drive_controller::GeomControllerBase::setup
bool setup(const std::vector< typename Controller::WheelParams > &wheel_params)
Definition: GeomController.h:46
GeomController.h
cob_omni_drive_controller::WheelControllerBase
Definition: WheelControllerBase.h:39
cob_omni_drive_controller::GeomControllerBase
Definition: GeomController.h:28
controller_interface::ControllerBase
cob_omni_drive_controller::WheelControllerBase< GeomMultiController >::setup
bool setup(ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: WheelControllerBase.h:42
hardware_interface::VelocityJointInterface
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
joint_command_interface.h
hardware_interface::RobotHW
controller_interface::MultiInterfaceController
cob_omni_drive_controller::WheelMultiController
Definition: control_multi_plugin.cpp:13
cob_omni_drive_controller::WheelMultiController::update
virtual void update(const ros::Time &time, const ros::Duration &period)
Definition: control_multi_plugin.cpp:36
cob_omni_drive_controller::WheelControllerBase< GeomMultiController >::updateCtrl
void updateCtrl(const ros::Time &time, const ros::Duration &period)
Definition: WheelControllerBase.h:80
cob_omni_drive_controller::WheelMultiController::init
virtual bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh)
Definition: control_multi_plugin.cpp:16
cob_omni_drive_controller::WheelControllerBase< GeomMultiController >::wheel_commands_
std::vector< WheelCommand > wheel_commands_
Definition: WheelControllerBase.h:128
ros::Time
cob_omni_drive_controller::GeomMultiController
Definition: control_multi_plugin.cpp:9
cob_omni_drive_controller::GeomControllerBase< hardware_interface::JointHandle, UndercarriageDirectCtrl >::steer_joints_
std::vector< hardware_interface::JointHandle > steer_joints_
Definition: GeomController.h:30
hardware_interface::PositionJointInterface
ros::Duration
ros::NodeHandle
cob_omni_drive_controller
Definition: UndercarriageCtrlGeomROS.h:24
multi_interface_controller.h


cob_omni_drive_controller
Author(s): Christian Connette, Mathias Lüdtke
autogenerated on Mon May 1 2023 02:44:36