hebiros_gazebo_controller.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include "ros/ros.h"
4 #include "hebiros_gazebo_group.h"
5 #include "hebiros_gazebo_joint.h"
6 
7 using namespace hebiros;
8 
10 
11 public:
12 
13  HebirosGazeboController() = default;
14 
15  static double ComputeForce(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
16  std::shared_ptr<HebirosGazeboJoint> hebiros_joint,
17  double position, double velocity, double effort, const ros::Duration& iteration_time);
18 
19  static double ComputePositionPID(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
20  std::shared_ptr<HebirosGazeboJoint> hebiros_joint,
21  double target_position, double position, const ros::Duration& iteration_time);
22 
23  static double ComputeVelocityPID(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
24  std::shared_ptr<HebirosGazeboJoint> hebiros_joint,
25  double target_velocity, double velocity, const ros::Duration& iteration_time);
26 
27  static double ComputeEffortPID(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
28  std::shared_ptr<HebirosGazeboJoint> hebiros_joint,
29  double target_effort, double effort, const ros::Duration& iteration_time);
30 
31  static void SetSettings(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
32  std::shared_ptr<HebirosGazeboJoint> hebiros_joint);
33 
34  static void ChangeSettings(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
35  std::shared_ptr<HebirosGazeboJoint> hebiros_joint);
36 
37  static void SetDefaultGains(std::shared_ptr<HebirosGazeboGroup> hebiros_group,
38  std::shared_ptr<HebirosGazeboJoint> hebiros_joint);
39 
40  static double Clip(double x, double low, double high);
41 
42 };
EIGEN_DEVICE_FUNC const Scalar & x


hebiros_gazebo_plugin
Author(s): Xavier Artache , Matthew Tesch
autogenerated on Thu Sep 3 2020 04:13:55