40 #include <orca/gazebo/GazeboServer.h> 41 #include <orca/gazebo/GazeboModel.h> 42 #include <orca/robot/RobotModel.h> 53 , std::shared_ptr<orca::robot::RobotModel> robot_kinematics);
57 ros::Publisher state_pub_;
58 ros::Publisher joint_states_pub_;
59 ros::Subscriber desired_torque_sub_;
60 Eigen::VectorXd torque_command_;
61 std::shared_ptr<orca::gazebo::GazeboModel> gz_model_;
62 orca_ros::RobotState state_;
63 sensor_msgs::JointState joint_states_;
64 std::shared_ptr<orca::robot::RobotModel> robot_kinematics_;
65 bool robot_compensates_gravity_ =
false;
66 bool first_command_received_ =
false;
Definition: RosWrapperBase.h:50
Definition: RosCartesianAccelerationPID.h:42
void desiredTorqueSubscriberCb(const orca_ros::JointTorqueCommand::ConstPtr &msg)
Definition: RosGazeboModel.cc:95
RosGazeboModel(std::shared_ptr< orca::gazebo::GazeboModel > gz_model, std::shared_ptr< orca::robot::RobotModel > robot_kinematics)
Definition: RosGazeboModel.cc:7
void publishRobotState()
Definition: RosGazeboModel.cc:64
Definition: RosGazeboModel.h:49