39 #include <orca/robot/RobotModel.h> 48 ,
public orca::robot::RobotModel
59 void currentStateSubscriberCb(
const orca_ros::RobotState::ConstPtr& msg);
62 ros::Subscriber robot_state_sub_;
64 Eigen::Matrix4d world_H_base_;
65 Eigen::VectorXd jointPos_;
66 Eigen::Matrix<double,6,1> baseVel_;
67 Eigen::VectorXd jointVel_;
68 Eigen::Vector3d gravity_;
70 bool initialized_ =
false;
72 ros::ServiceClient sc_getBaseFrame_;
73 ros::ServiceClient sc_getUrdfUrl_;
std::string getUrdfUrl()
Definition: RosRobotModelProxy.cc:64
RosRobotModelProxy(const std::string &robot_name)
Definition: RosRobotModelProxy.cc:5
Definition: RosWrapperBase.h:50
virtual ~RosRobotModelProxy()
Definition: RosRobotModelProxy.cc:37
Definition: RosCartesianAccelerationPID.h:42
std::string getBaseFrame()
Definition: RosRobotModelProxy.cc:54
Definition: RosRobotModelProxy.h:47