add support for anymal c

This commit is contained in:
Huang Zhenbiao 2024-10-16 22:59:11 +08:00
parent 0ff1b344e7
commit 85bd924bee
63 changed files with 7526 additions and 30 deletions

BIN
.images/anymal_c.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 81 KiB

View File

@ -23,17 +23,17 @@ namespace ocs2::legged_robot {
vector_t update(const rclcpp::Time &time, const rclcpp::Duration &period) override;
void loadSettings(const std::string &taskFile, bool verbose);
void loadSettings(const std::string &task_file, bool verbose);
protected:
nav_msgs::msg::Odometry getOdomMsg();
vector_t feetHeights_;
vector_t feet_heights_;
// Config
scalar_t footRadius_ = 0.02;
scalar_t imuProcessNoisePosition_ = 0.02;
scalar_t imuProcessNoiseVelocity_ = 0.02;
scalar_t foot_radius_ = 0.02;
scalar_t imu_process_noise_position_ = 0.02;
scalar_t imu_process_noise_velocity_ = 0.02;
scalar_t footProcessNoisePosition_ = 0.002;
scalar_t footSensorNoisePosition_ = 0.005;
scalar_t footSensorNoiseVelocity_ = 0.1;

View File

@ -125,6 +125,9 @@ namespace ocs2::legged_robot {
reference_file_ = auto_declare<std::string>("reference_file", reference_file_);
gait_file_ = auto_declare<std::string>("gait_file", gait_file_);
get_node()->get_parameter("update_rate", ctrl_comp_.frequency_);
RCLCPP_INFO(get_node()->get_logger(), "Controller Manager Update Rate: %d Hz", ctrl_comp_.frequency_);
// Load verbose parameter from the task file
verbose_ = false;
loadData::loadCppDataType(task_file_, "legged_robot_interface.verbose", verbose_);
@ -193,9 +196,6 @@ namespace ocs2::legged_robot {
observation_publisher_ = get_node()->create_publisher<ocs2_msgs::msg::MpcObservation>(
"legged_robot_mpc_observation", 10);
get_node()->get_parameter("update_rate", ctrl_comp_.frequency_);
RCLCPP_INFO(get_node()->get_logger(), "Controller Manager Update Rate: %d Hz", ctrl_comp_.frequency_);
return CallbackReturn::SUCCESS;
}
@ -229,7 +229,7 @@ namespace ocs2::legged_robot {
// Initial state
ctrl_comp_.observation_.state.setZero(
static_cast<long>(legged_interface_->getCentroidalModelInfo().stateDim));
updateStateEstimation(get_node()->now(), rclcpp::Duration(0, 200000));
updateStateEstimation(get_node()->now(), rclcpp::Duration(0, 1/ctrl_comp_.frequency_*1000000000));
ctrl_comp_.observation_.input.setZero(
static_cast<long>(legged_interface_->getCentroidalModelInfo().inputDim));
ctrl_comp_.observation_.mode = STANCE;

View File

@ -33,25 +33,24 @@ namespace ocs2::legged_robot {
const vector_t currentPose = ctrl_component_.observation_.state.segment<6>(6);
const Eigen::Matrix<scalar_t, 3, 1> zyx = currentPose.tail(3);
vector_t cmdVelRot = getRotationMatrixFromZyxEulerAngles(zyx) * cmdGoal.head(3);
vector_t cmd_vel_rot = getRotationMatrixFromZyxEulerAngles(zyx) * cmdGoal.head(3);
const scalar_t timeToTarget = time_to_target_;
const vector_t targetPose = [&]() {
vector_t target(6);
target(0) = currentPose(0) + cmdVelRot(0) * timeToTarget;
target(1) = currentPose(1) + cmdVelRot(1) * timeToTarget;
target(0) = currentPose(0) + cmd_vel_rot(0) * time_to_target_;
target(1) = currentPose(1) + cmd_vel_rot(1) * time_to_target_;
target(2) = command_height_;
target(3) = currentPose(3) + cmdGoal(3) * timeToTarget;
target(3) = currentPose(3) + cmdGoal(3) * time_to_target_;
target(4) = 0;
target(5) = 0;
return target;
}();
const scalar_t targetReachingTime = ctrl_component_.observation_.time + timeToTarget;
const scalar_t targetReachingTime = ctrl_component_.observation_.time + time_to_target_;
auto trajectories =
targetPoseToTargetTrajectories(targetPose, ctrl_component_.observation_, targetReachingTime);
trajectories.stateTrajectory[0].head(3) = cmdVelRot;
trajectories.stateTrajectory[1].head(3) = cmdVelRot;
trajectories.stateTrajectory[0].head(3) = cmd_vel_rot;
trajectories.stateTrajectory[1].head(3) = cmd_vel_rot;
referenceManagerPtr_->setTargetTrajectories(std::move(trajectories));
}

View File

@ -13,7 +13,8 @@
#include <ocs2_robotic_tools/common/RotationTransforms.h>
namespace ocs2::legged_robot {
KalmanFilterEstimate::KalmanFilterEstimate(PinocchioInterface pinocchio_interface, CentroidalModelInfo info,
KalmanFilterEstimate::KalmanFilterEstimate(PinocchioInterface pinocchio_interface,
CentroidalModelInfo info,
const PinocchioEndEffectorKinematics &ee_kinematics,
CtrlComponent &ctrl_component,
const rclcpp_lifecycle::LifecycleNode::SharedPtr &node)
@ -43,7 +44,7 @@ namespace ocs2::legged_robot {
q_.setIdentity(numState_, numState_);
p_ = 100. * q_;
r_.setIdentity(numObserve_, numObserve_);
feetHeights_.setZero(numContacts_);
feet_heights_.setZero(numContacts_);
ee_kinematics_->setPinocchioInterface(pinocchio_interface_);
}
@ -85,8 +86,8 @@ namespace ocs2::legged_robot {
const auto eeVel = ee_kinematics_->getVelocity(vector_t(), vector_t());
matrix_t q = matrix_t::Identity(numState_, numState_);
q.block(0, 0, 3, 3) = q_.block(0, 0, 3, 3) * imuProcessNoisePosition_;
q.block(3, 3, 3, 3) = q_.block(3, 3, 3, 3) * imuProcessNoiseVelocity_;
q.block(0, 0, 3, 3) = q_.block(0, 0, 3, 3) * imu_process_noise_position_;
q.block(3, 3, 3, 3) = q_.block(3, 3, 3, 3) * imu_process_noise_velocity_;
q.block(6, 6, dimContacts_, dimContacts_) =
q_.block(6, 6, dimContacts_, dimContacts_) * footProcessNoisePosition_;
@ -114,7 +115,7 @@ namespace ocs2::legged_robot {
r(rIndex3, rIndex3) = (isContact ? 1. : high_suspect_number) * r(rIndex3, rIndex3);
ps_.segment(3 * i, 3) = -eePos[i];
ps_.segment(3 * i, 3)[2] += footRadius_;
ps_.segment(3 * i, 3)[2] += foot_radius_;
vs_.segment(3 * i, 3) = -eeVel[i];
}
@ -122,7 +123,7 @@ namespace ocs2::legged_robot {
vector3_t accel = getRotationMatrixFromZyxEulerAngles(quatToZyx(quat_)) * linear_accel_local_ + g;
vector_t y(numObserve_);
y << ps_, vs_, feetHeights_;
y << ps_, vs_, feet_heights_;
xHat_ = a_ * xHat_ + b_ * accel;
matrix_t at = a_.transpose();
matrix_t pm = a_ * p_ * at + q;
@ -190,18 +191,18 @@ namespace ocs2::legged_robot {
return odom;
}
void KalmanFilterEstimate::loadSettings(const std::string &taskFile, bool verbose) {
void KalmanFilterEstimate::loadSettings(const std::string &task_file, const bool verbose) {
boost::property_tree::ptree pt;
read_info(taskFile, pt);
read_info(task_file, pt);
const std::string prefix = "kalmanFilter.";
if (verbose) {
std::cerr << "\n #### Kalman Filter Noise:";
std::cerr << "\n #### =============================================================================\n";
}
loadData::loadPtreeValue(pt, footRadius_, prefix + "footRadius", verbose);
loadData::loadPtreeValue(pt, imuProcessNoisePosition_, prefix + "imuProcessNoisePosition", verbose);
loadData::loadPtreeValue(pt, imuProcessNoiseVelocity_, prefix + "imuProcessNoiseVelocity", verbose);
loadData::loadPtreeValue(pt, foot_radius_, prefix + "footRadius", verbose);
loadData::loadPtreeValue(pt, imu_process_noise_position_, prefix + "imuProcessNoisePosition", verbose);
loadData::loadPtreeValue(pt, imu_process_noise_velocity_, prefix + "imuProcessNoiseVelocity", verbose);
loadData::loadPtreeValue(pt, footProcessNoisePosition_, prefix + "footProcessNoisePosition", verbose);
loadData::loadPtreeValue(pt, footSensorNoisePosition_, prefix + "footSensorNoisePosition", verbose);
loadData::loadPtreeValue(pt, footSensorNoiseVelocity_, prefix + "footSensorNoiseVelocity", verbose);

View File

@ -42,7 +42,7 @@ namespace ocs2::legged_robot {
void StateEstimateBase::updateContact() {
const size_t size = ctrl_component_.foot_force_state_interface_.size();
for (int i = 0; i < size; i++) {
contact_flag_[i] = ctrl_component_.foot_force_state_interface_[i].get().get_value() > 1;
contact_flag_[i] = ctrl_component_.foot_force_state_interface_[i].get().get_value() > 0.1;
}
}

View File

@ -0,0 +1,11 @@
cmake_minimum_required(VERSION 3.8)
project(anymal_c_description)
find_package(ament_cmake REQUIRED)
install(
DIRECTORY meshes xacro launch config urdf
DESTINATION share/${PROJECT_NAME}/
)
ament_package()

View File

@ -0,0 +1,29 @@
Copyright 2020, ANYbotics AG.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
3. Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

View File

@ -0,0 +1,34 @@
# Anybotics Anymal_C Description
This repository contains the urdf model of lite3.
![anymal_c](../../../.images/anymal_c.png)
Tested environment:
* Ubuntu 24.04
* ROS2 Jazzy
## Build
```bash
cd ~/ros2_ws
colcon build --packages-up-to anymal_c_description --symlink-install
```
## Visualize the robot
To visualize and check the configuration of the robot in rviz, simply launch:
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch anymal_c_description visualize.launch.py
```
## Launch ROS2 Control
### Mujoco Simulator
* OCS2 Quadruped Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch anymal_c_description ocs2_control.launch.py
```
* Legged Gym Controller
```bash
source ~/ros2_ws/install/setup.bash
ros2 launch anymal_c_description rl_control.launch.py
```

View File

@ -0,0 +1,255 @@
list
{
[0] stance
[1] trot
[2] standing_trot
[3] flying_trot
[4] pace
[5] standing_pace
[6] dynamic_walk
[7] static_walk
[8] amble
[9] lindyhop
[10] skipping
[11] pawup
}
stance
{
modeSequence
{
[0] STANCE
}
switchingTimes
{
[0] 0.0
[1] 0.5
}
}
trot
{
modeSequence
{
[0] LF_RH
[1] RF_LH
}
switchingTimes
{
[0] 0.0
[1] 0.35
[2] 0.70
}
}
standing_trot
{
modeSequence
{
[0] LF_RH
[1] STANCE
[2] RF_LH
[3] STANCE
}
switchingTimes
{
[0] 0.00
[1] 0.30
[2] 0.35
[3] 0.65
[4] 0.70
}
}
flying_trot
{
modeSequence
{
[0] LF_RH
[1] FLY
[2] RF_LH
[3] FLY
}
switchingTimes
{
[0] 0.00
[1] 0.27
[2] 0.30
[3] 0.57
[4] 0.60
}
}
pace
{
modeSequence
{
[0] LF_LH
[1] FLY
[2] RF_RH
[3] FLY
}
switchingTimes
{
[0] 0.0
[1] 0.28
[2] 0.30
[3] 0.58
[4] 0.60
}
}
standing_pace
{
modeSequence
{
[0] LF_LH
[1] STANCE
[2] RF_RH
[3] STANCE
}
switchingTimes
{
[0] 0.0
[1] 0.30
[2] 0.35
[3] 0.65
[4] 0.70
}
}
dynamic_walk
{
modeSequence
{
[0] LF_RF_RH
[1] RF_RH
[2] RF_LH_RH
[3] LF_RF_LH
[4] LF_LH
[5] LF_LH_RH
}
switchingTimes
{
[0] 0.0
[1] 0.2
[2] 0.3
[3] 0.5
[4] 0.7
[5] 0.8
[6] 1.0
}
}
static_walk
{
modeSequence
{
[0] LF_RF_RH
[1] RF_LH_RH
[2] LF_RF_LH
[3] LF_LH_RH
}
switchingTimes
{
[0] 0.0
[1] 0.3
[2] 0.6
[3] 0.9
[4] 1.2
}
}
amble
{
modeSequence
{
[0] RF_LH
[1] LF_LH
[2] LF_RH
[3] RF_RH
}
switchingTimes
{
[0] 0.0
[1] 0.15
[2] 0.40
[3] 0.55
[4] 0.80
}
}
lindyhop
{
modeSequence
{
[0] LF_RH
[1] STANCE
[2] RF_LH
[3] STANCE
[4] LF_LH
[5] RF_RH
[6] LF_LH
[7] STANCE
[8] RF_RH
[9] LF_LH
[10] RF_RH
[11] STANCE
}
switchingTimes
{
[0] 0.00 ; Step 1
[1] 0.35 ; Stance
[2] 0.45 ; Step 2
[3] 0.80 ; Stance
[4] 0.90 ; Tripple step
[5] 1.125 ;
[6] 1.35 ;
[7] 1.70 ; Stance
[8] 1.80 ; Tripple step
[9] 2.025 ;
[10] 2.25 ;
[11] 2.60 ; Stance
[12] 2.70 ;
}
}
skipping
{
modeSequence
{
[0] LF_RH
[1] FLY
[2] LF_RH
[3] FLY
[4] RF_LH
[5] FLY
[6] RF_LH
[7] FLY
}
switchingTimes
{
[0] 0.00
[1] 0.27
[2] 0.30
[3] 0.57
[4] 0.60
[5] 0.87
[6] 0.90
[7] 1.17
[8] 1.20
}
}
pawup
{
modeSequence
{
[0] RF_LH_RH
}
switchingTimes
{
[0] 0.0
[1] 2.0
}
}

View File

@ -0,0 +1,46 @@
targetDisplacementVelocity 0.5;
targetRotationVelocity 1.57;
comHeight 0.565;
defaultJointState
{
(0,0) -0.25 ; LF_HAA
(1,0) 0.60 ; LF_HFE
(2,0) -0.85 ; LF_KFE
(3,0) -0.25 ; LH_HAA
(4,0) -0.60 ; LH_HFE
(5,0) 0.85 ; LH_KFE
(6,0) 0.25 ; RF_HAA
(7,0) 0.60 ; RF_HFE
(8,0) -0.85 ; RF_KFE
(9,0) 0.25 ; RH_HAA
(10,0) -0.60 ; RH_HFE
(11,0) 0.85 ; RH_KFE
}
initialModeSchedule
{
modeSequence
{
[0] STANCE
[1] STANCE
}
eventTimes
{
[0] 0.5
}
}
defaultModeSequenceTemplate
{
modeSequence
{
[0] STANCE
}
switchingTimes
{
[0] 0.0
[1] 1.0
}
}

View File

@ -0,0 +1,318 @@
centroidalModelType 0 // 0: FullCentroidalDynamics, 1: Single Rigid Body Dynamics
legged_robot_interface
{
verbose false // show the loaded parameters
}
model_settings
{
positionErrorGain 0.0 ; 20.0
phaseTransitionStanceTime 0.4
verboseCppAd true
recompileLibrariesCppAd false
modelFolderCppAd /tmp/ocs2_quadruped_controller/anymal_c
}
swing_trajectory_config
{
liftOffVelocity 0.2
touchDownVelocity -0.4
swingHeight 0.1
touchdownAfterHorizon 0.2
swingTimeScale 0.15
}
; Multiple_Shooting SQP settings
sqp
{
nThreads 3
dt 0.015
sqpIteration 1
deltaTol 1e-4
g_max 1e-2
g_min 1e-6
inequalityConstraintMu 0.1
inequalityConstraintDelta 5.0
projectStateInputEqualityConstraints true
printSolverStatistics true
printSolverStatus false
printLinesearch false
useFeedbackPolicy true
integratorType RK2
threadPriority 50
}
; Multiple_Shooting IPM settings
ipm
{
nThreads 3
dt 0.015
ipmIteration 1
deltaTol 1e-4
g_max 10.0
g_min 1e-6
computeLagrangeMultipliers true
printSolverStatistics true
printSolverStatus false
printLinesearch false
useFeedbackPolicy true
integratorType RK2
threadPriority 50
initialBarrierParameter 1e-4
targetBarrierParameter 1e-4
barrierLinearDecreaseFactor 0.2
barrierSuperlinearDecreasePower 1.5
barrierReductionCostTol 1e-3
barrierReductionConstraintTol 1e-3
fractionToBoundaryMargin 0.995
usePrimalStepSizeForDual false
initialSlackLowerBound 1e-4
initialDualLowerBound 1e-4
initialSlackMarginRate 1e-2
initialDualMarginRate 1e-2
}
; DDP settings
ddp
{
algorithm SLQ
nThreads 3
threadPriority 50
maxNumIterations 1
minRelCost 1e-1
constraintTolerance 5e-3
displayInfo false
displayShortSummary false
checkNumericalStability false
debugPrintRollout false
AbsTolODE 1e-5
RelTolODE 1e-3
maxNumStepsPerSecond 10000
timeStep 0.015
backwardPassIntegratorType ODE45
constraintPenaltyInitialValue 20.0
constraintPenaltyIncreaseRate 2.0
preComputeRiccatiTerms true
useFeedbackPolicy false
strategy LINE_SEARCH
lineSearch
{
minStepLength 1e-2
maxStepLength 1.0
hessianCorrectionStrategy DIAGONAL_SHIFT
hessianCorrectionMultiple 1e-5
}
}
; Rollout settings
rollout
{
AbsTolODE 1e-5
RelTolODE 1e-3
timeStep 0.015
integratorType ODE45
maxNumStepsPerSecond 10000
checkNumericalStability false
}
mpc
{
timeHorizon 1.0 ; [s]
solutionTimeWindow -1 ; maximum [s]
coldStart false
debugPrint false
mpcDesiredFrequency 100 ; [Hz]
mrtDesiredFrequency 500 ; [Hz]
}
initialState
{
;; Normalized Centroidal Momentum: [linear, angular] ;;
(0,0) 0.0 ; vcom_x
(1,0) 0.0 ; vcom_y
(2,0) 0.0 ; vcom_z
(3,0) 0.0 ; L_x / robotMass
(4,0) 0.0 ; L_y / robotMass
(5,0) 0.0 ; L_z / robotMass
;; Base Pose: [position, orientation] ;;
(6,0) 0.0 ; p_base_x
(7,0) 0.0 ; p_base_y
(8,0) 0.575 ; p_base_z
(9,0) 0.0 ; theta_base_z
(10,0) 0.0 ; theta_base_y
(11,0) 0.0 ; theta_base_x
;; Leg Joint Positions: [LF, LH, RF, RH] ;;
(12,0) -0.25 ; LF_HAA
(13,0) 0.60 ; LF_HFE
(14,0) -0.85 ; LF_KFE
(15,0) -0.25 ; LH_HAA
(16,0) -0.60 ; LH_HFE
(17,0) 0.85 ; LH_KFE
(18,0) 0.25 ; RF_HAA
(19,0) 0.60 ; RF_HFE
(20,0) -0.85 ; RF_KFE
(21,0) 0.25 ; RH_HAA
(22,0) -0.60 ; RH_HFE
(23,0) 0.85 ; RH_KFE
}
; standard state weight matrix
Q
{
scaling 1e+0
;; Normalized Centroidal Momentum: [linear, angular] ;;
(0,0) 15.0 ; vcom_x
(1,1) 15.0 ; vcom_y
(2,2) 30.0 ; vcom_z
(3,3) 5.0 ; L_x / robotMass
(4,4) 10.0 ; L_y / robotMass
(5,5) 10.0 ; L_z / robotMass
;; Base Pose: [position, orientation] ;;
(6,6) 500.0 ; p_base_x
(7,7) 500.0 ; p_base_y
(8,8) 500.0 ; p_base_z
(9,9) 100.0 ; theta_base_z
(10,10) 200.0 ; theta_base_y
(11,11) 200.0 ; theta_base_x
;; Leg Joint Positions: [LF, LH, RF, RH] ;;
(12,12) 20.0 ; LF_HAA
(13,13) 20.0 ; LF_HFE
(14,14) 20.0 ; LF_KFE
(15,15) 20.0 ; LH_HAA
(16,16) 20.0 ; LH_HFE
(17,17) 20.0 ; LH_KFE
(18,18) 20.0 ; RF_HAA
(19,19) 20.0 ; RF_HFE
(20,20) 20.0 ; RF_KFE
(21,21) 20.0 ; RH_HAA
(22,22) 20.0 ; RH_HFE
(23,23) 20.0 ; RH_KFE
}
; control weight matrix
R
{
scaling 1e-3
;; Feet Contact Forces: [LF, RF, LH, RH] ;;
(0,0) 1.0 ; left_front_force
(1,1) 1.0 ; left_front_force
(2,2) 1.0 ; left_front_force
(3,3) 1.0 ; right_front_force
(4,4) 1.0 ; right_front_force
(5,5) 1.0 ; right_front_force
(6,6) 1.0 ; left_hind_force
(7,7) 1.0 ; left_hind_force
(8,8) 1.0 ; left_hind_force
(9,9) 1.0 ; right_hind_force
(10,10) 1.0 ; right_hind_force
(11,11) 1.0 ; right_hind_force
;; foot velocity relative to base: [LF, LH, RF, RH] (uses the Jacobian at nominal configuration) ;;
(12,12) 5000.0 ; x
(13,13) 5000.0 ; y
(14,14) 5000.0 ; z
(15,15) 5000.0 ; x
(16,16) 5000.0 ; y
(17,17) 5000.0 ; z
(18,18) 5000.0 ; x
(19,19) 5000.0 ; y
(20,20) 5000.0 ; z
(21,21) 5000.0 ; x
(22,22) 5000.0 ; y
(23,23) 5000.0 ; z
}
frictionConeSoftConstraint
{
frictionCoefficient 0.5
; relaxed log barrier parameters
mu 0.1
delta 5.0
}
selfCollision
{
; Self Collision raw object pairs
collisionObjectPairs
{
}
; Self Collision pairs
collisionLinkPairs
{
[0] "LF_SHANK, RF_SHANK"
[1] "LH_SHANK, RH_SHANK"
[2] "LF_SHANK, LH_SHANK"
[3] "RF_SHANK, RH_SHANK"
[4] "LF_FOOT, RF_FOOT"
[5] "LH_FOOT, RH_FOOT"
[6] "LF_FOOT, LH_FOOT"
[7] "RF_FOOT, RH_FOOT"
}
minimumDistance 0.05
; relaxed log barrier parameters
mu 1e-2
delta 1e-3
}
; Whole body control
torqueLimitsTask
{
(0,0) 80.0 ; HAA
(1,0) 80.0 ; HFE
(2,0) 80.0 ; KFE
}
frictionConeTask
{
frictionCoefficient 0.3
}
swingLegTask
{
kp 350
kd 37
}
weight
{
swingLeg 100
baseAccel 1
contactForce 0.01
}
; State Estimation
kalmanFilter
{
footRadius 0.03
imuProcessNoisePosition 0.02
imuProcessNoiseVelocity 0.02
footProcessNoisePosition 0.002
footSensorNoisePosition 0.005
footSensorNoiseVelocity 0.1
footHeightSensorNoise 0.01
}

View File

@ -0,0 +1,83 @@
# Controller Manager configuration
controller_manager:
ros__parameters:
update_rate: 500 # Hz
# Define the available controllers
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
imu_sensor_broadcaster:
type: imu_sensor_broadcaster/IMUSensorBroadcaster
unitree_guide_controller:
type: unitree_guide_controller/UnitreeGuideController
ocs2_quadruped_controller:
type: ocs2_quadruped_controller/Ocs2QuadrupedController
rl_quadruped_controller:
type: LH_quadruped_controller/LeggedGymController
imu_sensor_broadcaster:
ros__parameters:
sensor_name: "imu_sensor"
frame_id: "imu_link"
ocs2_quadruped_controller:
ros__parameters:
joints:
- LF_HAA
- LF_HFE
- LF_KFE
- LH_HAA
- LH_HFE
- LH_KFE
- RF_HAA
- RF_HFE
- RF_KFE
- RH_HAA
- RH_HFE
- RH_KFE
command_interfaces:
- effort
- position
- velocity
- kp
- kd
state_interfaces:
- effort
- position
- velocity
feet:
- LF_FOOT
- RF_FOOT
- LH_FOOT
- RH_FOOT
imu_name: "imu_sensor"
base_name: "base"
imu_interfaces:
- orientation.w
- orientation.x
- orientation.y
- orientation.z
- angular_velocity.x
- angular_velocity.y
- angular_velocity.z
- linear_acceleration.x
- linear_acceleration.y
- linear_acceleration.z
foot_force_name: "foot_force"
foot_force_interfaces:
- LF
- RF
- LH
- RH

View File

@ -0,0 +1,383 @@
Panels:
- Class: rviz_common/Displays
Help Height: 138
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /RobotModel1
Splitter Ratio: 0.5
Tree Height: 303
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
FL_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_calf_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_hip_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FL_thigh_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_calf_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_hip_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
FR_thigh_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Link Tree Style: Links in Alphabetic Order
RL_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_calf_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_hip_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RL_thigh_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_calf:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_calf_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_foot:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_hip:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_hip_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_thigh:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
RR_thigh_rotor:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_chin:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_face:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_laserscan_link_left:
Alpha: 1
Show Axes: false
Show Trail: false
camera_laserscan_link_right:
Alpha: 1
Show Axes: false
Show Trail: false
camera_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_optical_chin:
Alpha: 1
Show Axes: false
Show Trail: false
camera_optical_face:
Alpha: 1
Show Axes: false
Show Trail: false
camera_optical_left:
Alpha: 1
Show Axes: false
Show Trail: false
camera_optical_rearDown:
Alpha: 1
Show Axes: false
Show Trail: false
camera_optical_right:
Alpha: 1
Show Axes: false
Show Trail: false
camera_rearDown:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
camera_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
imu_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
trunk:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ultraSound_face:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ultraSound_left:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
ultraSound_right:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/Orbit
Distance: 0.8687032461166382
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.017344314604997635
Y: -0.0033522010780870914
Z: -0.09058035165071487
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.49539798498153687
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.8403961062431335
Saved: ~
Window Geometry:
Displays:
collapsed: true
Height: 630
Hide Left Dock: true
Hide Right Dock: true
QMainWindow State: 000000ff00000000fd0000000400000000000001f40000043cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000700000043c000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000043cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000043c000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003130000005efc0100000002fb0000000800540069006d0065010000000000000313000002fb00fffffffb0000000800540069006d0065010000000000000450000000000000000000000313000001b800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 787
X: 763
Y: 351

View File

@ -0,0 +1,109 @@
import os
import xacro
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import OpaqueFunction, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
package_description = "anymal_c_description"
package_controller = "ocs2_quadruped_controller"
def process_xacro():
pkg_path = os.path.join(get_package_share_directory(package_description))
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
robot_description_config = xacro.process_file(xacro_file)
return robot_description_config.toxml()
def generate_launch_description():
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.rviz")
robot_description = process_xacro()
robot_controllers = PathJoinSubstitution(
[
FindPackageShare(package_description),
"config",
"robot_control.yaml",
]
)
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
parameters=[
{
'publish_frequency': 20.0,
'use_tf_static': True,
'robot_description': robot_description,
'ignore_timestamp': True
}
],
)
controller_manager = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_controllers,
{
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf',
'robot.urdf'),
'task_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
'task.info'),
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
'ocs2', 'reference.info'),
'gait_file': os.path.join(get_package_share_directory(package_description), 'config',
'ocs2', 'gait.info')
}],
output="both",
)
joint_state_publisher = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster",
"--controller-manager", "/controller_manager"],
)
imu_sensor_broadcaster = Node(
package="controller_manager",
executable="spawner",
arguments=["imu_sensor_broadcaster",
"--controller-manager", "/controller_manager"],
)
ocs2_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
)
return LaunchDescription([
Node(
package='rviz2',
executable='rviz2',
name='rviz_ocs2',
output='screen',
arguments=["-d", rviz_config_file]
),
robot_state_publisher,
controller_manager,
joint_state_publisher,
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_publisher,
on_exit=[imu_sensor_broadcaster],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=imu_sensor_broadcaster,
on_exit=[ocs2_controller],
)
),
])

View File

@ -0,0 +1,112 @@
import os
import xacro
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
package_description = "anymal_c_description"
def process_xacro(context):
robot_type_value = context.launch_configurations['robot_type']
pkg_path = os.path.join(get_package_share_directory(package_description))
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
return (robot_description_config.toxml(), robot_type_value)
def launch_setup(context, *args, **kwargs):
(robot_description, robot_type) = process_xacro(context)
robot_controllers = PathJoinSubstitution(
[
FindPackageShare(package_description),
"config",
"robot_control.yaml",
]
)
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
parameters=[
{
'publish_frequency': 20.0,
'use_tf_static': True,
'robot_description': robot_description,
'ignore_timestamp': True
}
],
)
controller_manager = Node(
package="controller_manager",
executable="ros2_control_node",
parameters=[robot_controllers],
output="both",
)
joint_state_publisher = Node(
package="controller_manager",
executable="spawner",
arguments=["joint_state_broadcaster",
"--controller-manager", "/controller_manager"],
)
imu_sensor_broadcaster = Node(
package="controller_manager",
executable="spawner",
arguments=["imu_sensor_broadcaster",
"--controller-manager", "/controller_manager"],
)
unitree_guide_controller = Node(
package="controller_manager",
executable="spawner",
arguments=["unitree_guide_controller", "--controller-manager", "/controller_manager"],
)
return [
robot_state_publisher,
controller_manager,
joint_state_publisher,
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_publisher,
on_exit=[imu_sensor_broadcaster],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=imu_sensor_broadcaster,
on_exit=[unitree_guide_controller],
)
),
]
def generate_launch_description():
robot_type_arg = DeclareLaunchArgument(
'robot_type',
default_value='a1',
description='Type of the robot'
)
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
return LaunchDescription([
robot_type_arg,
OpaqueFunction(function=launch_setup),
Node(
package='rviz2',
executable='rviz2',
name='rviz_ocs2',
output='screen',
arguments=["-d", rviz_config_file]
)
])

View File

@ -0,0 +1,49 @@
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node
import xacro
package_description = "anymal_c_description"
def process_xacro():
pkg_path = os.path.join(get_package_share_directory(package_description))
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
robot_description_config = xacro.process_file(xacro_file)
return robot_description_config.toxml()
def generate_launch_description():
rviz_config_file = os.path.join(get_package_share_directory(package_description), "config", "visualize_urdf.rviz")
robot_description = process_xacro()
return LaunchDescription([
Node(
package='rviz2',
executable='rviz2',
name='rviz_ocs2',
output='screen',
arguments=["-d", rviz_config_file]
),
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[
{
'publish_frequency': 100.0,
'use_tf_static': True,
'robot_description': robot_description
}
],
),
Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher',
output='screen',
)
])

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 194 KiB

View File

@ -0,0 +1,115 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.81.16 commit date:2019-11-20, commit time:14:27, hash:26bd5ebd42e3</authoring_tool>
</contributor>
<created>2020-01-07T14:47:32</created>
<modified>2020-01-07T14:47:32</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
<effect id="battery-effect">
<profile_COMMON>
<newparam sid="battery-surface">
<surface type="2D">
<init_from>battery</init_from>
</surface>
</newparam>
<newparam sid="battery-sampler">
<sampler2D>
<source>battery-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<lambert>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<diffuse>
<texture texture="battery-sampler" texcoord="UVMap"/>
</diffuse>
<index_of_refraction>
<float sid="ior">1.45</float>
</index_of_refraction>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_images>
<image id="battery" name="battery">
<init_from>battery.jpg</init_from>
</image>
</library_images>
<library_materials>
<material id="battery-material" name="battery">
<instance_effect url="#battery-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">-0.225881 -0.06249898 -0.03684729 -0.225881 -0.06249898 0.03725165 -0.225881 0.06249898 -0.03684729 -0.225881 0.06249898 0.03725165 0.232213 -0.06249898 -0.03684729 0.232213 -0.06249898 0.03725165 0.232213 0.06249898 -0.03684729 0.232213 0.06249898 0.03725165</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="18">-1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map">
<float_array id="Cube-mesh-map-array" count="72">0.8431081 0.2728654 1 0 1 0.2728654 0.6862162 1 0.8431079 0 0.8431081 1 0.8431081 0.5457308 1 0.2728654 1 0.5457308 0.6862159 0 0.5293241 1 0.5293239 0 0.264662 0 0.5293239 0.9999999 0.2646622 0.9999999 0.264662 0.9999999 0 0 0.2646618 0 0.8431081 0.2728654 0.8431081 0 1 0 0.6862162 1 0.6862161 0 0.8431079 0 0.8431081 0.5457308 0.8431081 0.2728654 1 0.2728654 0.6862159 0 0.6862161 1 0.5293241 1 0.264662 0 0.5293238 0 0.5293239 0.9999999 0.264662 0.9999999 1.73529e-7 0.9999999 0 0</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<triangles material="battery-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map" offset="2" set="0"/>
<p>1 0 0 2 0 1 0 0 2 3 1 3 6 1 4 2 1 5 7 2 6 4 2 7 6 2 8 5 3 9 0 3 10 4 3 11 6 4 12 0 4 13 2 4 14 3 5 15 5 5 16 7 5 17 1 0 18 3 0 19 2 0 20 3 1 21 7 1 22 6 1 23 7 2 24 5 2 25 4 2 26 5 3 27 1 3 28 0 3 29 6 4 30 4 4 31 0 4 32 3 5 33 1 5 34 5 5 35</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="AM3_Battery_LP" name="AM3 Battery LP" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 -0.03329167 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh" name="AM3 Battery LP">
<bind_material>
<technique_common>
<instance_material symbol="battery-material" target="#battery-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 111 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 165 KiB

View File

@ -0,0 +1,115 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.82.7 commit date:2020-02-12, commit time:16:20, hash:77d23b0bd76f</authoring_tool>
</contributor>
<created>2020-02-20T10:55:16</created>
<modified>2020-02-20T10:55:16</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
<effect id="depth_camera-effect">
<profile_COMMON>
<newparam sid="depth_camera-surface">
<surface type="2D">
<init_from>depth_camera</init_from>
</surface>
</newparam>
<newparam sid="depth_camera-sampler">
<sampler2D>
<source>depth_camera-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<lambert>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<diffuse>
<texture texture="depth_camera-sampler" texcoord="UVMap"/>
</diffuse>
<index_of_refraction>
<float sid="ior">1.45</float>
</index_of_refraction>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_images>
<image id="depth_camera" name="depth_camera">
<init_from>depth_camera.jpg</init_from>
</image>
</library_images>
<library_materials>
<material id="depth_camera-material" name="depth_camera">
<instance_effect url="#depth_camera-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="Cube-mesh" name="Cube">
<mesh>
<source id="Cube-mesh-positions">
<float_array id="Cube-mesh-positions-array" count="24">0 -0.04699999 -0.01968461 0 -0.04699999 0.01951932 0 0.04699999 -0.01968461 0 0.04699999 0.01951932 0.03039997 -0.04699999 -0.01968461 0.03039997 -0.04699999 0.01951932 0.03039997 0.04699999 -0.01968461 0.03039997 0.04699999 0.01951932</float_array>
<technique_common>
<accessor source="#Cube-mesh-positions-array" count="8" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-normals">
<float_array id="Cube-mesh-normals-array" count="18">-1 0 0 1 0 0 0 0 1 0 -1 0 0 1 0 0 0 -1</float_array>
<technique_common>
<accessor source="#Cube-mesh-normals-array" count="6" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="Cube-mesh-map">
<float_array id="Cube-mesh-map-array" count="72">0.2816218 0.7056847 0.5632433 0 0.5632433 0.7056847 1.60564e-7 0.7056847 0.2816215 0 0.2816217 0.7056847 0.7816217 0.7056846 1 0 1 0.7056846 0.5632433 0.7056847 0.344865 1 0.344865 0.7056847 0.7816216 0.7056847 0.5632434 1 0.5632433 0.7056847 0.7816217 0 0.5632433 0.7056846 0.5632434 0 0.2816218 0.7056847 0.2816217 0 0.5632433 0 1.60564e-7 0.7056847 0 0 0.2816215 0 0.7816217 0.7056846 0.7816217 0 1 0 0.5632433 0.7056847 0.5632433 1 0.344865 1 0.7816216 0.7056847 0.7816218 1 0.5632434 1 0.7816217 0 0.7816216 0.7056846 0.5632433 0.7056846</float_array>
<technique_common>
<accessor source="#Cube-mesh-map-array" count="36" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="Cube-mesh-vertices">
<input semantic="POSITION" source="#Cube-mesh-positions"/>
</vertices>
<triangles material="depth_camera-material" count="12">
<input semantic="VERTEX" source="#Cube-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#Cube-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#Cube-mesh-map" offset="2" set="0"/>
<p>1 0 0 2 0 1 0 0 2 7 1 3 4 1 4 6 1 5 3 2 6 5 2 7 7 2 8 1 3 9 4 3 10 5 3 11 7 4 12 2 4 13 3 4 14 6 5 15 0 5 16 2 5 17 1 0 18 3 0 19 2 0 20 7 1 21 5 1 22 4 1 23 3 2 24 1 2 25 5 2 26 1 3 27 0 3 28 4 3 29 7 4 30 6 4 31 2 4 32 6 5 33 4 5 34 0 5 35</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="Realsense_LP" name="Realsense LP" type="NODE">
<matrix sid="transform">1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1</matrix>
<instance_geometry url="#Cube-mesh" name="Realsense LP">
<bind_material>
<technique_common>
<instance_material symbol="depth_camera-material" target="#depth_camera-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 186 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 174 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 295 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 185 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 166 KiB

View File

@ -0,0 +1,115 @@
<?xml version="1.0" encoding="utf-8"?>
<COLLADA xmlns="http://www.collada.org/2005/11/COLLADASchema" version="1.4.1" xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance">
<asset>
<contributor>
<author>Blender User</author>
<authoring_tool>Blender 2.81.16 commit date:2019-11-20, commit time:14:27, hash:26bd5ebd42e3</authoring_tool>
</contributor>
<created>2020-01-13T19:28:23</created>
<modified>2020-01-13T19:28:23</modified>
<unit name="meter" meter="1"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
<effect id="hatch-effect">
<profile_COMMON>
<newparam sid="hatch-surface">
<surface type="2D">
<init_from>hatch</init_from>
</surface>
</newparam>
<newparam sid="hatch-sampler">
<sampler2D>
<source>hatch-surface</source>
</sampler2D>
</newparam>
<technique sid="common">
<lambert>
<emission>
<color sid="emission">0 0 0 1</color>
</emission>
<diffuse>
<texture texture="hatch-sampler" texcoord="UVMap"/>
</diffuse>
<index_of_refraction>
<float sid="ior">1.45</float>
</index_of_refraction>
</lambert>
</technique>
</profile_COMMON>
</effect>
</library_effects>
<library_images>
<image id="hatch" name="hatch">
<init_from>hatch.jpg</init_from>
</image>
</library_images>
<library_materials>
<material id="hatch-material" name="hatch">
<instance_effect url="#hatch-effect"/>
</material>
</library_materials>
<library_geometries>
<geometry id="AM3_Application_Hatch_Detailed_HD_002-mesh" name="AM3 Application Hatch Detailed HD.002">
<mesh>
<source id="AM3_Application_Hatch_Detailed_HD_002-mesh-positions">
<float_array id="AM3_Application_Hatch_Detailed_HD_002-mesh-positions-array" count="96">-76.90127 -64.71254 0 -76.90127 -64.71254 5.500071 -76.90127 64.71254 0 -76.90127 64.71254 5.500071 76.90133 -64.71254 0 76.90133 -64.71254 5.500071 76.90133 64.71254 0 76.90133 64.71254 5.500071 -80.46286 11.54165 0 -91.00833 3.847216 0 -91.00833 -3.847217 0 -80.46286 -11.54165 0 -80.46286 -11.54165 5.500071 -91.00833 -3.847217 5.500071 -91.00833 3.847217 5.500071 -80.46286 11.54165 5.500071 80.46292 -11.54165 0 91.00839 -3.847217 0 91.00839 3.847217 0 80.46292 11.54165 0 80.46292 11.54165 5.500071 91.00839 3.847216 5.500071 91.00839 -3.847217 5.500071 80.46292 -11.54165 5.500071 -80.46286 38.12709 5.500071 80.46292 38.12709 0 -80.46286 38.12709 0 80.46292 38.12709 5.500071 -80.46286 -38.12709 0 80.46292 -38.12709 5.500071 -80.46286 -38.12709 5.500071 80.46292 -38.12709 0</float_array>
<technique_common>
<accessor source="#AM3_Application_Hatch_Detailed_HD_002-mesh-positions-array" count="32" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="AM3_Application_Hatch_Detailed_HD_002-mesh-normals">
<float_array id="AM3_Application_Hatch_Detailed_HD_002-mesh-normals-array" count="63">-0.9911455 0.1327809 0 0 1 0 0.9911455 -0.1327809 0 0 -1 0 0 0 1 0 0 1 1 0 0 0.5894234 0.8078244 0 0.5894234 -0.8078244 0 -1 0 0 -0.5894234 -0.8078244 0 -0.5894234 0.8078243 -2.12521e-7 0.9911454 0.1327813 0 -0.9911454 -0.1327813 0 -0.9911454 0.1327813 0 0.9911454 -0.1327813 0 0 0 1 0.5894235 0.8078243 2.12521e-7 -0.5894234 0.8078244 0 0.9911455 0.1327809 0 -0.9911455 -0.1327809 0</float_array>
<technique_common>
<accessor source="#AM3_Application_Hatch_Detailed_HD_002-mesh-normals-array" count="21" stride="3">
<param name="X" type="float"/>
<param name="Y" type="float"/>
<param name="Z" type="float"/>
</accessor>
</technique_common>
</source>
<source id="AM3_Application_Hatch_Detailed_HD_002-mesh-map">
<float_array id="AM3_Application_Hatch_Detailed_HD_002-mesh-map-array" count="276">0.8547119 0.7845032 0.8910338 0.6826047 0.8910338 0.7845032 0.8547118 0.6826048 0.8910338 0 0.8910338 0.6826047 0.963678 0.5650011 0.927356 0.7110616 0.927356 0.5650011 0.891034 0.7845032 0.927356 0.1018984 0.927356 0.7845032 0.1755681 0.9420632 0 0.07750421 0.1755678 0.05793678 0.679144 0.9420632 0.5035759 0.05793678 0.6791438 0.05793678 0.503576 0.9420632 0.4527625 0 0.5035759 0.05793678 0.4527627 1 0.4019491 0 0.4527625 0 0.4019494 1 0.3511358 0.05793678 0.4019491 0 0.963678 0.1460605 0.927356 0.2921209 0.927356 0.1460605 0.963678 0.2921209 0.927356 0.3343942 0.927356 0.2921209 0.963678 0.3343942 0.927356 0.3766674 0.927356 0.3343942 0.963678 0.3766674 0.927356 0.4189407 0.927356 0.3766674 0.927356 0.7971531 0.963678 0.7110617 0.963678 0.7971532 0.963678 0.07171952 1 0 1 0.07171952 0.8547119 0.9672312 0.8910339 0.9423143 0.8910339 0.9672312 0.8547119 0.9423143 0.8910339 0.8705947 0.8910339 0.9423143 0.963678 0 0.927356 0.1460605 0.9273561 0 0.8547118 0.9224958 0.6791438 0.05793678 0.8547117 0.07750409 0.8547119 0.8705947 0.8910338 0.7845032 0.8910339 0.8705947 0.891034 0.1018984 0.927356 0 0.927356 0.1018984 0.351136 0.9420632 0.1755678 0.05793678 0.3511358 0.05793678 0.963678 0.4189407 0.927356 0.5650011 0.927356 0.4189407 0.8547119 0.7845032 0.8547118 0.6826048 0.8910338 0.6826047 0.8547118 0.6826048 0.8547118 0 0.8910338 0 0.963678 0.5650011 0.963678 0.7110616 0.927356 0.7110616 0.891034 0.7845032 0.891034 0.1018984 0.927356 0.1018984 0.1755681 0.9420632 0 0.9224959 0 0.07750421 0.679144 0.9420632 0.503576 0.9420632 0.5035759 0.05793678 0.503576 0.9420632 0.4527627 1 0.4527625 0 0.4527627 1 0.4019494 1 0.4019491 0 0.4019494 1 0.351136 0.9420632 0.3511358 0.05793678 0.963678 0.1460605 0.963678 0.2921209 0.927356 0.2921209 0.963678 0.2921209 0.963678 0.3343942 0.927356 0.3343942 0.963678 0.3343942 0.963678 0.3766674 0.927356 0.3766674 0.963678 0.3766674 0.963678 0.4189407 0.927356 0.4189407 0.927356 0.7971531 0.927356 0.7110616 0.963678 0.7110617 0.963678 0.07171952 0.963678 0 1 0 0.8547119 0.9672312 0.8547119 0.9423143 0.8910339 0.9423143 0.8547119 0.9423143 0.8547119 0.8705947 0.8910339 0.8705947 0.963678 0 0.963678 0.1460605 0.927356 0.1460605 0.8547118 0.9224958 0.679144 0.9420632 0.6791438 0.05793678 0.8547119 0.8705947 0.8547119 0.7845032 0.8910338 0.7845032 0.891034 0.1018984 0.891034 0 0.927356 0 0.351136 0.9420632 0.1755681 0.9420632 0.1755678 0.05793678 0.963678 0.4189407 0.963678 0.5650011 0.927356 0.5650011</float_array>
<technique_common>
<accessor source="#AM3_Application_Hatch_Detailed_HD_002-mesh-map-array" count="138" stride="2">
<param name="S" type="float"/>
<param name="T" type="float"/>
</accessor>
</technique_common>
</source>
<vertices id="AM3_Application_Hatch_Detailed_HD_002-mesh-vertices">
<input semantic="POSITION" source="#AM3_Application_Hatch_Detailed_HD_002-mesh-positions"/>
</vertices>
<triangles material="hatch-material" count="46">
<input semantic="VERTEX" source="#AM3_Application_Hatch_Detailed_HD_002-mesh-vertices" offset="0"/>
<input semantic="NORMAL" source="#AM3_Application_Hatch_Detailed_HD_002-mesh-normals" offset="1"/>
<input semantic="TEXCOORD" source="#AM3_Application_Hatch_Detailed_HD_002-mesh-map" offset="2" set="0"/>
<p>24 0 0 2 0 1 26 0 2 3 1 3 6 1 4 2 1 5 29 2 6 4 2 7 31 2 8 5 3 9 0 3 10 4 3 11 30 4 12 5 4 13 29 4 14 24 4 15 20 4 16 27 4 17 15 4 18 21 4 19 20 4 20 14 5 21 22 5 22 21 5 23 13 4 24 23 4 25 22 4 26 27 6 27 19 6 28 25 6 29 20 7 30 18 7 31 19 7 32 21 6 33 17 6 34 18 6 35 22 8 36 16 8 37 17 8 38 30 9 39 11 9 40 28 9 41 12 10 42 10 10 43 11 10 44 13 9 45 9 9 46 10 9 47 14 11 48 8 11 49 9 11 50 7 12 51 25 12 52 6 12 53 3 4 54 27 4 55 7 4 56 15 9 57 26 9 58 8 9 59 1 13 60 28 13 61 0 13 62 12 4 63 29 4 64 23 4 65 23 6 66 31 6 67 16 6 68 24 14 69 3 14 70 2 14 71 3 1 72 7 1 73 6 1 74 29 15 75 5 15 76 4 15 77 5 3 78 1 3 79 0 3 80 30 4 81 1 4 82 5 4 83 24 4 84 15 4 85 20 4 86 15 16 87 14 16 88 21 16 89 14 4 90 13 4 91 22 4 92 13 4 93 12 4 94 23 4 95 27 6 96 20 6 97 19 6 98 20 17 99 21 17 100 18 17 101 21 6 102 22 6 103 17 6 104 22 8 105 23 8 106 16 8 107 30 9 108 12 9 109 11 9 110 12 10 111 13 10 112 10 10 113 13 9 114 14 9 115 9 9 116 14 18 117 15 18 118 8 18 119 7 19 120 27 19 121 25 19 122 3 4 123 24 4 124 27 4 125 15 9 126 24 9 127 26 9 128 1 20 129 30 20 130 28 20 131 12 4 132 30 4 133 29 4 134 23 6 135 29 6 136 31 6 137</p>
</triangles>
</mesh>
</geometry>
</library_geometries>
<library_visual_scenes>
<visual_scene id="Scene" name="Scene">
<node id="AM3_Application_Hatch_LP" name="AM3 Application Hatch LP" type="NODE">
<matrix sid="transform">0.001006675 0 0 0 0 9.99987e-4 0 0 0 0 9.99987e-4 0 0 0 0 1</matrix>
<instance_geometry url="#AM3_Application_Hatch_Detailed_HD_002-mesh" name="AM3 Application Hatch LP">
<bind_material>
<technique_common>
<instance_material symbol="hatch-material" target="#hatch-material">
<bind_vertex_input semantic="UVMap" input_semantic="TEXCOORD" input_set="0"/>
</instance_material>
</technique_common>
</bind_material>
</instance_geometry>
</node>
</visual_scene>
</library_visual_scenes>
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>

Binary file not shown.

After

Width:  |  Height:  |  Size: 103 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 227 KiB

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 180 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 276 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 107 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 165 KiB

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 231 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 213 KiB

File diff suppressed because one or more lines are too long

Binary file not shown.

After

Width:  |  Height:  |  Size: 152 KiB

View File

@ -0,0 +1,21 @@
<?xml version="1.0"?>
<package format="2">
<name>anymal_c_description</name>
<version>0.0.0</version>
<description>The anymal_c_description package</description>
<license>BSD-3</license>
<author email="lisler@anybotics.com">Linus Isler</author>
<maintainer email="lisler@anybotics.com">Linus Isler</maintainer>
<maintainer email="rdiethelm@anybotics.com">Remo Diethelm</maintainer>
<exec_depend>xacro</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>imu_sensor_broadcaster</exec_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,195 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="GazeboSystem" type="system">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<joint name="FR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="FL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HR_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipX">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_HipY">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="HL_Knee">
<command_interface name="effort" initial_value="0.0"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="orientation.w"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
</ros2_control>
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters>$(find anymal_c_description)/config/gazebo.yaml</parameters>
</plugin>
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
</plugin>
</gazebo>
<gazebo reference="trunk">
<mu1>0.6</mu1>
<mu2>0.6</mu2>
<self_collide>1</self_collide>
<visual>
<material>
<ambient>.05 .05 .05 1.0</ambient>
<diffuse>.05 .05 .05 1.0</diffuse>
<specular>.05 .05 .05 1.0</specular>
</material>
</visual>
</gazebo>
<gazebo reference="imu_link">
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>500</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
<imu>
<angular_velocity>
<x>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
</x>
<y>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
</y>
<z>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>2e-4</stddev>-->
<!-- <bias_mean>0.0000075</bias_mean>-->
<!-- <bias_stddev>0.0000008</bias_stddev>-->
<!-- </noise>-->
</z>
</angular_velocity>
<linear_acceleration>
<x>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
</x>
<y>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
</y>
<z>
<!-- <noise type="gaussian">-->
<!-- <mean>0.0</mean>-->
<!-- <stddev>1.7e-2</stddev>-->
<!-- <bias_mean>0.1</bias_mean>-->
<!-- <bias_stddev>0.001</bias_stddev>-->
<!-- </noise>-->
</z>
</linear_acceleration>
</imu>
</sensor>
</gazebo>
<gazebo reference="imu_joint">
<disableFixedJointLumping>true</disableFixedJointLumping>
</gazebo>
</robot>

View File

@ -0,0 +1,30 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<joint name="imu_joint" type="fixed">
<parent link="TORSO"/>
<child link="imu_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size=".001 .001 .001"/>
</geometry>
</collision>
</link>
</robot>

View File

@ -0,0 +1,36 @@
<?xml version="1.0"?>
<robot>
<material name="black">
<color rgba="0.0 0.0 0.0 1.0"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="deep-grey">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="grey">
<color rgba="0.2 0.2 0.2 1.0"/>
</material>
<material name="light-grey">
<color rgba="0.35 0.35 0.35 1.0"/>
</material>
<material name="silver">
<color rgba="${233/255} ${233/255} ${216/255} 1.0"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</robot>

View File

@ -0,0 +1,16 @@
<?xml version="1.0"?>
<robot name="x30" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find anymal_c_description)/xacro/body.xacro"/>
<xacro:include filename="$(find anymal_c_description)/xacro/materials.xacro"/>
<xacro:arg name="GAZEBO" default="false"/>
<xacro:if value="$(arg GAZEBO)">
<xacro:include filename="$(find anymal_c_description)/xacro/gazebo.xacro"/>
</xacro:if>
<xacro:unless value="$(arg GAZEBO)">
<xacro:include filename="$(find anymal_c_description)/xacro/ros2_control.xacro"/>
</xacro:unless>
</robot>

View File

@ -0,0 +1,176 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<ros2_control name="UnitreeSystem" type="system">
<hardware>
<plugin>hardware_unitree_mujoco/HardwareUnitree</plugin>
</hardware>
<joint name="RF_HAA">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RF_HFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RF_KFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LF_HAA">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LF_HFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LF_KFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RH_HAA">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RH_HFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="RH_KFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LH_HAA">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LH_HFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="LH_KFE">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<command_interface name="kp"/>
<command_interface name="kd"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<sensor name="imu_sensor">
<state_interface name="orientation.w"/>
<state_interface name="orientation.x"/>
<state_interface name="orientation.y"/>
<state_interface name="orientation.z"/>
<state_interface name="angular_velocity.x"/>
<state_interface name="angular_velocity.y"/>
<state_interface name="angular_velocity.z"/>
<state_interface name="linear_acceleration.x"/>
<state_interface name="linear_acceleration.y"/>
<state_interface name="linear_acceleration.z"/>
</sensor>
<sensor name="foot_force">
<state_interface name="RF"/>
<state_interface name="LF"/>
<state_interface name="RH"/>
<state_interface name="LH"/>
</sensor>
</ros2_control>
</robot>

View File

@ -1,4 +1,4 @@
model_name: "model_0702.pt"
model_name: "rl_sar.pt"
framework: "isaacgym"
rows: 4
cols: 3