load joint names and feet names from config file
This commit is contained in:
parent
86bbcf75e6
commit
979e3228b3
|
@ -25,14 +25,20 @@
|
||||||
#include "SwitchedModelReferenceManager.h"
|
#include "SwitchedModelReferenceManager.h"
|
||||||
|
|
||||||
namespace ocs2::legged_robot {
|
namespace ocs2::legged_robot {
|
||||||
class LeggedInterface : public RobotInterface {
|
class LeggedInterface final : public RobotInterface {
|
||||||
public:
|
public:
|
||||||
LeggedInterface(const std::string &task_file, const std::string &urdf_file, const std::string &reference_file,
|
LeggedInterface(const std::string &task_file,
|
||||||
|
const std::string &urdf_file,
|
||||||
|
const std::string &reference_file,
|
||||||
bool use_hard_friction_cone_constraint = false);
|
bool use_hard_friction_cone_constraint = false);
|
||||||
|
|
||||||
~LeggedInterface() override = default;
|
~LeggedInterface() override = default;
|
||||||
|
|
||||||
virtual void setupOptimalControlProblem(const std::string &task_file, const std::string &urdf_file,
|
void setupJointNames(const std::vector<std::string> &joint_names,
|
||||||
|
const std::vector<std::string> &foot_names);
|
||||||
|
|
||||||
|
void setupOptimalControlProblem(const std::string &task_file,
|
||||||
|
const std::string &urdf_file,
|
||||||
const std::string &reference_file,
|
const std::string &reference_file,
|
||||||
bool verbose);
|
bool verbose);
|
||||||
|
|
||||||
|
@ -41,15 +47,11 @@ namespace ocs2::legged_robot {
|
||||||
const ModelSettings &modelSettings() const { return model_settings_; }
|
const ModelSettings &modelSettings() const { return model_settings_; }
|
||||||
const ddp::Settings &ddpSettings() const { return ddp_settings_; }
|
const ddp::Settings &ddpSettings() const { return ddp_settings_; }
|
||||||
const mpc::Settings &mpcSettings() const { return mpc_settings_; }
|
const mpc::Settings &mpcSettings() const { return mpc_settings_; }
|
||||||
const rollout::Settings &rolloutSettings() const { return rollout_settings_; }
|
|
||||||
const sqp::Settings &sqpSettings() { return sqp_settings_; }
|
const sqp::Settings &sqpSettings() { return sqp_settings_; }
|
||||||
const ipm::Settings &ipmSettings() { return ipm_settings_; }
|
|
||||||
|
|
||||||
const vector_t &getInitialState() const { return initial_state_; }
|
|
||||||
const RolloutBase &getRollout() const { return *rollout_ptr_; }
|
const RolloutBase &getRollout() const { return *rollout_ptr_; }
|
||||||
PinocchioInterface &getPinocchioInterface() { return *pinocchio_interface_ptr_; }
|
PinocchioInterface &getPinocchioInterface() { return *pinocchio_interface_ptr_; }
|
||||||
const CentroidalModelInfo &getCentroidalModelInfo() const { return centroidal_model_info_; }
|
const CentroidalModelInfo &getCentroidalModelInfo() const { return centroidal_model_info_; }
|
||||||
PinocchioGeometryInterface &getGeometryInterface() { return *geometry_interface_ptr_; }
|
|
||||||
|
|
||||||
std::shared_ptr<SwitchedModelReferenceManager> getSwitchedModelReferenceManagerPtr() const {
|
std::shared_ptr<SwitchedModelReferenceManager> getSwitchedModelReferenceManagerPtr() const {
|
||||||
return reference_manager_ptr_;
|
return reference_manager_ptr_;
|
||||||
|
@ -62,14 +64,14 @@ namespace ocs2::legged_robot {
|
||||||
}
|
}
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual void setupModel(const std::string &task_file, const std::string &urdf_file,
|
void setupModel(const std::string &task_file, const std::string &urdf_file,
|
||||||
const std::string &reference_file);
|
const std::string &reference_file);
|
||||||
|
|
||||||
virtual void setupReferenceManager(const std::string &taskFile, const std::string &urdfFile,
|
void setupReferenceManager(const std::string &taskFile, const std::string &urdfFile,
|
||||||
const std::string &referenceFile,
|
const std::string &referenceFile,
|
||||||
bool verbose);
|
bool verbose);
|
||||||
|
|
||||||
virtual void setupPreComputation(const std::string &taskFile, const std::string &urdfFile,
|
void setupPreComputation(const std::string &taskFile, const std::string &urdfFile,
|
||||||
const std::string &referenceFile,
|
const std::string &referenceFile,
|
||||||
bool verbose);
|
bool verbose);
|
||||||
|
|
||||||
|
|
|
@ -131,6 +131,7 @@ namespace ocs2::legged_robot {
|
||||||
|
|
||||||
// Hardware Parameters
|
// Hardware Parameters
|
||||||
joint_names_ = auto_declare<std::vector<std::string> >("joints", joint_names_);
|
joint_names_ = auto_declare<std::vector<std::string> >("joints", joint_names_);
|
||||||
|
feet_names_ = auto_declare<std::vector<std::string> >("feet", feet_names_);
|
||||||
command_interface_types_ =
|
command_interface_types_ =
|
||||||
auto_declare<std::vector<std::string> >("command_interfaces", command_interface_types_);
|
auto_declare<std::vector<std::string> >("command_interfaces", command_interface_types_);
|
||||||
state_interface_types_ =
|
state_interface_types_ =
|
||||||
|
@ -226,12 +227,15 @@ namespace ocs2::legged_robot {
|
||||||
|
|
||||||
if (mpc_running_ == false) {
|
if (mpc_running_ == false) {
|
||||||
// Initial state
|
// Initial state
|
||||||
ctrl_comp_.observation_.state.setZero(static_cast<long>(legged_interface_->getCentroidalModelInfo().stateDim));
|
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, 200000));
|
||||||
ctrl_comp_.observation_.input.setZero(static_cast<long>(legged_interface_->getCentroidalModelInfo().inputDim));
|
ctrl_comp_.observation_.input.setZero(
|
||||||
|
static_cast<long>(legged_interface_->getCentroidalModelInfo().inputDim));
|
||||||
ctrl_comp_.observation_.mode = STANCE;
|
ctrl_comp_.observation_.mode = STANCE;
|
||||||
|
|
||||||
const TargetTrajectories target_trajectories({ctrl_comp_.observation_.time}, {ctrl_comp_.observation_.state},
|
const TargetTrajectories target_trajectories({ctrl_comp_.observation_.time},
|
||||||
|
{ctrl_comp_.observation_.state},
|
||||||
{ctrl_comp_.observation_.input});
|
{ctrl_comp_.observation_.input});
|
||||||
|
|
||||||
// Set the first observation and command and wait for optimization to finish
|
// Set the first observation and command and wait for optimization to finish
|
||||||
|
@ -273,6 +277,7 @@ namespace ocs2::legged_robot {
|
||||||
|
|
||||||
void Ocs2QuadrupedController::setupLeggedInterface() {
|
void Ocs2QuadrupedController::setupLeggedInterface() {
|
||||||
legged_interface_ = std::make_shared<LeggedInterface>(task_file_, urdf_file_, reference_file_);
|
legged_interface_ = std::make_shared<LeggedInterface>(task_file_, urdf_file_, reference_file_);
|
||||||
|
legged_interface_->setupJointNames(joint_names_, feet_names_);
|
||||||
legged_interface_->setupOptimalControlProblem(task_file_, urdf_file_, reference_file_, verbose_);
|
legged_interface_->setupOptimalControlProblem(task_file_, urdf_file_, reference_file_, verbose_);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -73,6 +73,7 @@ namespace ocs2::legged_robot {
|
||||||
|
|
||||||
CtrlComponent ctrl_comp_;
|
CtrlComponent ctrl_comp_;
|
||||||
std::vector<std::string> joint_names_;
|
std::vector<std::string> joint_names_;
|
||||||
|
std::vector<std::string> feet_names_;
|
||||||
std::vector<std::string> command_interface_types_;
|
std::vector<std::string> command_interface_types_;
|
||||||
std::vector<std::string> state_interface_types_;
|
std::vector<std::string> state_interface_types_;
|
||||||
|
|
||||||
|
@ -99,6 +100,7 @@ namespace ocs2::legged_robot {
|
||||||
// Foot Force Sensor
|
// Foot Force Sensor
|
||||||
std::string foot_force_name_;
|
std::string foot_force_name_;
|
||||||
std::vector<std::string> foot_force_interface_types_;
|
std::vector<std::string> foot_force_interface_types_;
|
||||||
|
|
||||||
double default_kp_ = 0;
|
double default_kp_ = 0;
|
||||||
double default_kd_ = 6;
|
double default_kd_ = 6;
|
||||||
|
|
||||||
|
|
|
@ -67,15 +67,6 @@ namespace ocs2::legged_robot {
|
||||||
// load setting from loading file
|
// load setting from loading file
|
||||||
model_settings_ = loadModelSettings(task_file, "model_settings", verbose);
|
model_settings_ = loadModelSettings(task_file, "model_settings", verbose);
|
||||||
|
|
||||||
// Todo : load settings from ros param
|
|
||||||
model_settings_.jointNames = {
|
|
||||||
"FL_hip_joint", "FL_thigh_joint", "FL_calf_joint",
|
|
||||||
"FR_hip_joint", "FR_thigh_joint", "FR_calf_joint",
|
|
||||||
"RL_hip_joint", "RL_thigh_joint", "RL_calf_joint",
|
|
||||||
"RR_hip_joint", "RR_thigh_joint", "RR_calf_joint"
|
|
||||||
};
|
|
||||||
model_settings_.contactNames3DoF = {"FL_foot", "FR_foot", "RL_foot", "RR_foot"};
|
|
||||||
|
|
||||||
mpc_settings_ = mpc::loadSettings(task_file, "mpc", verbose);
|
mpc_settings_ = mpc::loadSettings(task_file, "mpc", verbose);
|
||||||
ddp_settings_ = ddp::loadSettings(task_file, "ddp", verbose);
|
ddp_settings_ = ddp::loadSettings(task_file, "ddp", verbose);
|
||||||
sqp_settings_ = sqp::loadSettings(task_file, "sqp", verbose);
|
sqp_settings_ = sqp::loadSettings(task_file, "sqp", verbose);
|
||||||
|
@ -84,6 +75,12 @@ namespace ocs2::legged_robot {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void LeggedInterface::setupJointNames(const std::vector<std::string> &joint_names,
|
||||||
|
const std::vector<std::string> &foot_names) {
|
||||||
|
model_settings_.jointNames = joint_names;
|
||||||
|
model_settings_.contactNames3DoF = foot_names;
|
||||||
|
}
|
||||||
|
|
||||||
void LeggedInterface::setupOptimalControlProblem(const std::string &task_file,
|
void LeggedInterface::setupOptimalControlProblem(const std::string &task_file,
|
||||||
const std::string &urdf_file,
|
const std::string &urdf_file,
|
||||||
const std::string &reference_file,
|
const std::string &reference_file,
|
||||||
|
|
|
@ -101,7 +101,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "a1_description"
|
package_description = "a1_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_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_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
|
@ -102,7 +102,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "aliengo_description"
|
package_description = "aliengo_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_controller],
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
robot_type_arg = DeclareLaunchArgument(
|
|
||||||
'robot_type',
|
|
||||||
default_value='aliengo',
|
|
||||||
description='Type of the robot'
|
|
||||||
)
|
|
||||||
|
|
||||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
|
@ -103,7 +103,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "b2_description"
|
package_description = "b2_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_controller],
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
robot_type_arg = DeclareLaunchArgument(
|
|
||||||
'robot_type',
|
|
||||||
default_value='b2',
|
|
||||||
description='Type of the robot'
|
|
||||||
)
|
|
||||||
|
|
||||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
|
@ -101,7 +101,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "go1_description"
|
package_description = "go1_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_controller],
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
robot_type_arg = DeclareLaunchArgument(
|
|
||||||
'robot_type',
|
|
||||||
default_value='go1',
|
|
||||||
description='Type of the robot'
|
|
||||||
)
|
|
||||||
|
|
||||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
|
@ -101,7 +101,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "go2_description"
|
package_description = "go2_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_controller],
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
robot_type_arg = DeclareLaunchArgument(
|
|
||||||
'robot_type',
|
|
||||||
default_value='go2',
|
|
||||||
description='Type of the robot'
|
|
||||||
)
|
|
||||||
|
|
||||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
|
@ -129,7 +129,7 @@ ocs2_quadruped_controller:
|
||||||
- position
|
- position
|
||||||
- velocity
|
- velocity
|
||||||
|
|
||||||
feet_names:
|
feet:
|
||||||
- FL_foot
|
- FL_foot
|
||||||
- FR_foot
|
- FR_foot
|
||||||
- RL_foot
|
- RL_foot
|
||||||
|
|
|
@ -3,26 +3,26 @@ import os
|
||||||
import xacro
|
import xacro
|
||||||
from ament_index_python.packages import get_package_share_directory
|
from ament_index_python.packages import get_package_share_directory
|
||||||
from launch import LaunchDescription
|
from launch import LaunchDescription
|
||||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
from launch.actions import OpaqueFunction, RegisterEventHandler
|
||||||
from launch.event_handlers import OnProcessExit
|
from launch.event_handlers import OnProcessExit
|
||||||
from launch.substitutions import PathJoinSubstitution
|
from launch.substitutions import PathJoinSubstitution
|
||||||
from launch_ros.actions import Node
|
from launch_ros.actions import Node
|
||||||
from launch_ros.substitutions import FindPackageShare
|
from launch_ros.substitutions import FindPackageShare
|
||||||
from sympy.physics.vector.printing import params
|
|
||||||
|
|
||||||
package_description = "cyberdog_description"
|
package_description = "cyberdog_description"
|
||||||
package_controller = "ocs2_quadruped_controller"
|
package_controller = "ocs2_quadruped_controller"
|
||||||
|
|
||||||
def process_xacro(context):
|
|
||||||
robot_type_value = context.launch_configurations['robot_type']
|
def process_xacro():
|
||||||
pkg_path = os.path.join(get_package_share_directory(package_description))
|
pkg_path = os.path.join(get_package_share_directory(package_description))
|
||||||
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
xacro_file = os.path.join(pkg_path, 'xacro', 'robot.xacro')
|
||||||
robot_description_config = xacro.process_file(xacro_file, mappings={'robot_type': robot_type_value})
|
robot_description_config = xacro.process_file(xacro_file)
|
||||||
return (robot_description_config.toxml(), robot_type_value)
|
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")
|
||||||
|
|
||||||
def launch_setup(context, *args, **kwargs):
|
robot_description = process_xacro()
|
||||||
(robot_description, robot_type) = process_xacro(context)
|
|
||||||
robot_controllers = PathJoinSubstitution(
|
robot_controllers = PathJoinSubstitution(
|
||||||
[
|
[
|
||||||
FindPackageShare(package_description),
|
FindPackageShare(package_description),
|
||||||
|
@ -50,7 +50,8 @@ def launch_setup(context, *args, **kwargs):
|
||||||
executable="ros2_control_node",
|
executable="ros2_control_node",
|
||||||
parameters=[robot_controllers,
|
parameters=[robot_controllers,
|
||||||
{
|
{
|
||||||
'urdf_file': os.path.join(get_package_share_directory(package_description), 'urdf', 'robot.urdf'),
|
'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_file': os.path.join(get_package_share_directory(package_description), 'config', 'ocs2',
|
||||||
'task.info'),
|
'task.info'),
|
||||||
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
'reference_file': os.path.join(get_package_share_directory(package_description), 'config',
|
||||||
|
@ -81,7 +82,15 @@ def launch_setup(context, *args, **kwargs):
|
||||||
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
arguments=["ocs2_quadruped_controller", "--controller-manager", "/controller_manager"]
|
||||||
)
|
)
|
||||||
|
|
||||||
return [
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='rviz2',
|
||||||
|
executable='rviz2',
|
||||||
|
name='rviz_ocs2',
|
||||||
|
output='screen',
|
||||||
|
arguments=["-d", rviz_config_file]
|
||||||
|
),
|
||||||
|
|
||||||
robot_state_publisher,
|
robot_state_publisher,
|
||||||
controller_manager,
|
controller_manager,
|
||||||
joint_state_publisher,
|
joint_state_publisher,
|
||||||
|
@ -97,26 +106,4 @@ def launch_setup(context, *args, **kwargs):
|
||||||
on_exit=[ocs2_controller],
|
on_exit=[ocs2_controller],
|
||||||
)
|
)
|
||||||
),
|
),
|
||||||
]
|
|
||||||
|
|
||||||
|
|
||||||
def generate_launch_description():
|
|
||||||
robot_type_arg = DeclareLaunchArgument(
|
|
||||||
'robot_type',
|
|
||||||
default_value='go1',
|
|
||||||
description='Type of the robot'
|
|
||||||
)
|
|
||||||
|
|
||||||
rviz_config_file = os.path.join(get_package_share_directory(package_controller), "config", "visualize_ocs2.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]
|
|
||||||
)
|
|
||||||
])
|
])
|
||||||
|
|
Loading…
Reference in New Issue