add pd controller
This commit is contained in:
parent
5f9a55440e
commit
5825c3cac2
|
@ -0,0 +1,66 @@
|
|||
cmake_minimum_required(VERSION 3.8)
|
||||
project(leg_pd_controller)
|
||||
|
||||
if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
|
||||
add_compile_options(-Wall -Wextra -Wpedantic)
|
||||
endif ()
|
||||
|
||||
set(CMAKE_BUILD_TYPE Release)
|
||||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
|
||||
|
||||
set(CONTROLLER_INCLUDE_DEPENDS
|
||||
pluginlib
|
||||
rcpputils
|
||||
controller_interface
|
||||
realtime_tools
|
||||
)
|
||||
|
||||
# find dependencies
|
||||
find_package(ament_cmake REQUIRED)
|
||||
foreach (Dependency IN ITEMS ${CONTROLLER_INCLUDE_DEPENDS})
|
||||
find_package(${Dependency} REQUIRED)
|
||||
endforeach ()
|
||||
|
||||
add_library(${PROJECT_NAME} SHARED
|
||||
src/LegPdController.cpp
|
||||
)
|
||||
target_include_directories(${PROJECT_NAME}
|
||||
PUBLIC
|
||||
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
|
||||
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>")
|
||||
ament_target_dependencies(
|
||||
${PROJECT_NAME} PUBLIC
|
||||
${CONTROLLER_INCLUDE_DEPENDS}
|
||||
)
|
||||
|
||||
pluginlib_export_plugin_description_file(controller_interface leg_pd_controller.xml)
|
||||
|
||||
install(
|
||||
DIRECTORY include/
|
||||
DESTINATION include/${PROJECT_NAME}
|
||||
)
|
||||
|
||||
install(
|
||||
TARGETS ${PROJECT_NAME}
|
||||
EXPORT export_${PROJECT_NAME}
|
||||
ARCHIVE DESTINATION lib/${PROJECT_NAME}
|
||||
LIBRARY DESTINATION lib/${PROJECT_NAME}
|
||||
RUNTIME DESTINATION bin
|
||||
)
|
||||
|
||||
ament_export_dependencies(${CONTROLLER_INCLUDE_DEPENDS})
|
||||
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
|
||||
|
||||
if (BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
# the following line skips the linter which checks for copyrights
|
||||
# comment the line when a copyright and license is added to all source files
|
||||
set(ament_cmake_copyright_FOUND TRUE)
|
||||
# the following line skips cpplint (only works in a git repo)
|
||||
# comment the line when this package is in a git repo and when
|
||||
# a copyright and license is added to all source files
|
||||
set(ament_cmake_cpplint_FOUND TRUE)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif ()
|
||||
|
||||
ament_package()
|
|
@ -0,0 +1,202 @@
|
|||
|
||||
Apache License
|
||||
Version 2.0, January 2004
|
||||
http://www.apache.org/licenses/
|
||||
|
||||
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
|
||||
|
||||
1. Definitions.
|
||||
|
||||
"License" shall mean the terms and conditions for use, reproduction,
|
||||
and distribution as defined by Sections 1 through 9 of this document.
|
||||
|
||||
"Licensor" shall mean the copyright owner or entity authorized by
|
||||
the copyright owner that is granting the License.
|
||||
|
||||
"Legal Entity" shall mean the union of the acting entity and all
|
||||
other entities that control, are controlled by, or are under common
|
||||
control with that entity. For the purposes of this definition,
|
||||
"control" means (i) the power, direct or indirect, to cause the
|
||||
direction or management of such entity, whether by contract or
|
||||
otherwise, or (ii) ownership of fifty percent (50%) or more of the
|
||||
outstanding shares, or (iii) beneficial ownership of such entity.
|
||||
|
||||
"You" (or "Your") shall mean an individual or Legal Entity
|
||||
exercising permissions granted by this License.
|
||||
|
||||
"Source" form shall mean the preferred form for making modifications,
|
||||
including but not limited to software source code, documentation
|
||||
source, and configuration files.
|
||||
|
||||
"Object" form shall mean any form resulting from mechanical
|
||||
transformation or translation of a Source form, including but
|
||||
not limited to compiled object code, generated documentation,
|
||||
and conversions to other media types.
|
||||
|
||||
"Work" shall mean the work of authorship, whether in Source or
|
||||
Object form, made available under the License, as indicated by a
|
||||
copyright notice that is included in or attached to the work
|
||||
(an example is provided in the Appendix below).
|
||||
|
||||
"Derivative Works" shall mean any work, whether in Source or Object
|
||||
form, that is based on (or derived from) the Work and for which the
|
||||
editorial revisions, annotations, elaborations, or other modifications
|
||||
represent, as a whole, an original work of authorship. For the purposes
|
||||
of this License, Derivative Works shall not include works that remain
|
||||
separable from, or merely link (or bind by name) to the interfaces of,
|
||||
the Work and Derivative Works thereof.
|
||||
|
||||
"Contribution" shall mean any work of authorship, including
|
||||
the original version of the Work and any modifications or additions
|
||||
to that Work or Derivative Works thereof, that is intentionally
|
||||
submitted to Licensor for inclusion in the Work by the copyright owner
|
||||
or by an individual or Legal Entity authorized to submit on behalf of
|
||||
the copyright owner. For the purposes of this definition, "submitted"
|
||||
means any form of electronic, verbal, or written communication sent
|
||||
to the Licensor or its representatives, including but not limited to
|
||||
communication on electronic mailing lists, source code control systems,
|
||||
and issue tracking systems that are managed by, or on behalf of, the
|
||||
Licensor for the purpose of discussing and improving the Work, but
|
||||
excluding communication that is conspicuously marked or otherwise
|
||||
designated in writing by the copyright owner as "Not a Contribution."
|
||||
|
||||
"Contributor" shall mean Licensor and any individual or Legal Entity
|
||||
on behalf of whom a Contribution has been received by Licensor and
|
||||
subsequently incorporated within the Work.
|
||||
|
||||
2. Grant of Copyright License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
copyright license to reproduce, prepare Derivative Works of,
|
||||
publicly display, publicly perform, sublicense, and distribute the
|
||||
Work and such Derivative Works in Source or Object form.
|
||||
|
||||
3. Grant of Patent License. Subject to the terms and conditions of
|
||||
this License, each Contributor hereby grants to You a perpetual,
|
||||
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
|
||||
(except as stated in this section) patent license to make, have made,
|
||||
use, offer to sell, sell, import, and otherwise transfer the Work,
|
||||
where such license applies only to those patent claims licensable
|
||||
by such Contributor that are necessarily infringed by their
|
||||
Contribution(s) alone or by combination of their Contribution(s)
|
||||
with the Work to which such Contribution(s) was submitted. If You
|
||||
institute patent litigation against any entity (including a
|
||||
cross-claim or counterclaim in a lawsuit) alleging that the Work
|
||||
or a Contribution incorporated within the Work constitutes direct
|
||||
or contributory patent infringement, then any patent licenses
|
||||
granted to You under this License for that Work shall terminate
|
||||
as of the date such litigation is filed.
|
||||
|
||||
4. Redistribution. You may reproduce and distribute copies of the
|
||||
Work or Derivative Works thereof in any medium, with or without
|
||||
modifications, and in Source or Object form, provided that You
|
||||
meet the following conditions:
|
||||
|
||||
(a) You must give any other recipients of the Work or
|
||||
Derivative Works a copy of this License; and
|
||||
|
||||
(b) You must cause any modified files to carry prominent notices
|
||||
stating that You changed the files; and
|
||||
|
||||
(c) You must retain, in the Source form of any Derivative Works
|
||||
that You distribute, all copyright, patent, trademark, and
|
||||
attribution notices from the Source form of the Work,
|
||||
excluding those notices that do not pertain to any part of
|
||||
the Derivative Works; and
|
||||
|
||||
(d) If the Work includes a "NOTICE" text file as part of its
|
||||
distribution, then any Derivative Works that You distribute must
|
||||
include a readable copy of the attribution notices contained
|
||||
within such NOTICE file, excluding those notices that do not
|
||||
pertain to any part of the Derivative Works, in at least one
|
||||
of the following places: within a NOTICE text file distributed
|
||||
as part of the Derivative Works; within the Source form or
|
||||
documentation, if provided along with the Derivative Works; or,
|
||||
within a display generated by the Derivative Works, if and
|
||||
wherever such third-party notices normally appear. The contents
|
||||
of the NOTICE file are for informational purposes only and
|
||||
do not modify the License. You may add Your own attribution
|
||||
notices within Derivative Works that You distribute, alongside
|
||||
or as an addendum to the NOTICE text from the Work, provided
|
||||
that such additional attribution notices cannot be construed
|
||||
as modifying the License.
|
||||
|
||||
You may add Your own copyright statement to Your modifications and
|
||||
may provide additional or different license terms and conditions
|
||||
for use, reproduction, or distribution of Your modifications, or
|
||||
for any such Derivative Works as a whole, provided Your use,
|
||||
reproduction, and distribution of the Work otherwise complies with
|
||||
the conditions stated in this License.
|
||||
|
||||
5. Submission of Contributions. Unless You explicitly state otherwise,
|
||||
any Contribution intentionally submitted for inclusion in the Work
|
||||
by You to the Licensor shall be under the terms and conditions of
|
||||
this License, without any additional terms or conditions.
|
||||
Notwithstanding the above, nothing herein shall supersede or modify
|
||||
the terms of any separate license agreement you may have executed
|
||||
with Licensor regarding such Contributions.
|
||||
|
||||
6. Trademarks. This License does not grant permission to use the trade
|
||||
names, trademarks, service marks, or product names of the Licensor,
|
||||
except as required for reasonable and customary use in describing the
|
||||
origin of the Work and reproducing the content of the NOTICE file.
|
||||
|
||||
7. Disclaimer of Warranty. Unless required by applicable law or
|
||||
agreed to in writing, Licensor provides the Work (and each
|
||||
Contributor provides its Contributions) on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
|
||||
implied, including, without limitation, any warranties or conditions
|
||||
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
|
||||
PARTICULAR PURPOSE. You are solely responsible for determining the
|
||||
appropriateness of using or redistributing the Work and assume any
|
||||
risks associated with Your exercise of permissions under this License.
|
||||
|
||||
8. Limitation of Liability. In no event and under no legal theory,
|
||||
whether in tort (including negligence), contract, or otherwise,
|
||||
unless required by applicable law (such as deliberate and grossly
|
||||
negligent acts) or agreed to in writing, shall any Contributor be
|
||||
liable to You for damages, including any direct, indirect, special,
|
||||
incidental, or consequential damages of any character arising as a
|
||||
result of this License or out of the use or inability to use the
|
||||
Work (including but not limited to damages for loss of goodwill,
|
||||
work stoppage, computer failure or malfunction, or any and all
|
||||
other commercial damages or losses), even if such Contributor
|
||||
has been advised of the possibility of such damages.
|
||||
|
||||
9. Accepting Warranty or Additional Liability. While redistributing
|
||||
the Work or Derivative Works thereof, You may choose to offer,
|
||||
and charge a fee for, acceptance of support, warranty, indemnity,
|
||||
or other liability obligations and/or rights consistent with this
|
||||
License. However, in accepting such obligations, You may act only
|
||||
on Your own behalf and on Your sole responsibility, not on behalf
|
||||
of any other Contributor, and only if You agree to indemnify,
|
||||
defend, and hold each Contributor harmless for any liability
|
||||
incurred by, or claims asserted against, such Contributor by reason
|
||||
of your accepting any such warranty or additional liability.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
||||
|
||||
APPENDIX: How to apply the Apache License to your work.
|
||||
|
||||
To apply the Apache License to your work, attach the following
|
||||
boilerplate notice, with the fields enclosed by brackets "[]"
|
||||
replaced with your own identifying information. (Don't include
|
||||
the brackets!) The text should be enclosed in the appropriate
|
||||
comment syntax for the file format. We also recommend that a
|
||||
file or class name and description of purpose be included on the
|
||||
same "printed page" as the copyright notice for easier
|
||||
identification within third-party archives.
|
||||
|
||||
Copyright [yyyy] [name of copyright owner]
|
||||
|
||||
Licensed under the Apache License, Version 2.0 (the "License");
|
||||
you may not use this file except in compliance with the License.
|
||||
You may obtain a copy of the License at
|
||||
|
||||
http://www.apache.org/licenses/LICENSE-2.0
|
||||
|
||||
Unless required by applicable law or agreed to in writing, software
|
||||
distributed under the License is distributed on an "AS IS" BASIS,
|
||||
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
See the License for the specific language governing permissions and
|
||||
limitations under the License.
|
|
@ -0,0 +1,6 @@
|
|||
# Leg PD Controller
|
||||
|
||||
```bash
|
||||
cd ~/ros2_ws
|
||||
colcon build --packages-up-to leg_pd_controller
|
||||
```
|
|
@ -0,0 +1,68 @@
|
|||
//
|
||||
// Created by tlab-uav on 24-9-19.
|
||||
//
|
||||
|
||||
#ifndef LEGPDCONTROLLER_H
|
||||
#define LEGPDCONTROLLER_H
|
||||
#include <controller_interface/chainable_controller_interface.hpp>
|
||||
#include <controller_interface/controller_interface.hpp>
|
||||
|
||||
|
||||
namespace leg_pd_controller {
|
||||
class LegPdController : public controller_interface::ChainableControllerInterface {
|
||||
public:
|
||||
controller_interface::CallbackReturn on_init() override;
|
||||
|
||||
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
|
||||
|
||||
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
|
||||
|
||||
controller_interface::CallbackReturn on_configure(
|
||||
const rclcpp_lifecycle::State &previous_state) override;
|
||||
|
||||
controller_interface::CallbackReturn on_activate(
|
||||
const rclcpp_lifecycle::State &previous_state) override;
|
||||
|
||||
controller_interface::CallbackReturn on_deactivate(
|
||||
const rclcpp_lifecycle::State &previous_state) override;
|
||||
|
||||
bool on_set_chained_mode(bool chained_mode) override;
|
||||
|
||||
controller_interface::return_type update_and_write_commands(
|
||||
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||
|
||||
protected:
|
||||
std::vector<hardware_interface::CommandInterface> on_export_reference_interfaces() override;
|
||||
|
||||
controller_interface::return_type update_reference_from_subscribers(
|
||||
const rclcpp::Time &time, const rclcpp::Duration &period) override;
|
||||
|
||||
std::vector<double> joint_effort_command_;
|
||||
std::vector<double> joint_position_command_;
|
||||
std::vector<double> joint_velocities_command_;
|
||||
std::vector<double> joint_kp_command_;
|
||||
std::vector<double> joint_kd_command_;
|
||||
|
||||
std::vector<std::string> joint_names_;
|
||||
|
||||
std::vector<std::string> state_interface_types_;
|
||||
std::vector<std::string> reference_interface_types_;
|
||||
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> >
|
||||
joint_effort_command_interface_;
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface> >
|
||||
joint_position_state_interface_;
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface> >
|
||||
joint_velocity_state_interface_;
|
||||
|
||||
std::unordered_map<
|
||||
std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface> > *>
|
||||
state_interface_map_ = {
|
||||
{"position", &joint_position_state_interface_},
|
||||
{"velocity", &joint_velocity_state_interface_}
|
||||
};
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
#endif //LEGPDCONTROLLER_H
|
|
@ -0,0 +1,9 @@
|
|||
<library path="leg_pd_controller">
|
||||
<class name="leg_pd_controller/LegPdController"
|
||||
type="leg_pd_controller::LegPdController"
|
||||
base_class_type="controller_interface::ChainableControllerInterface">
|
||||
<description>
|
||||
PD controller for simulation which only support effort command input
|
||||
</description>
|
||||
</class>
|
||||
</library>
|
|
@ -0,0 +1,18 @@
|
|||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>leg_pd_controller</name>
|
||||
<version>0.0.0</version>
|
||||
<description>TODO: Package description</description>
|
||||
<maintainer email="biao876990970@hotmail.com">Huang Zhenbiao</maintainer>
|
||||
<license>Apache-2.0</license>
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
</package>
|
|
@ -0,0 +1,117 @@
|
|||
//
|
||||
// Created by tlab-uav on 24-9-19.
|
||||
//
|
||||
|
||||
#include "leg_pd_controller/LegPdController.h"
|
||||
|
||||
namespace leg_pd_controller {
|
||||
using config_type = controller_interface::interface_configuration_type;
|
||||
|
||||
controller_interface::CallbackReturn LegPdController::on_init() {
|
||||
try {
|
||||
joint_names_ = auto_declare<std::vector<std::string> >("joints", joint_names_);
|
||||
reference_interface_types_ =
|
||||
auto_declare<std::vector<std::string> >("reference_interfaces", reference_interface_types_);
|
||||
state_interface_types_ = auto_declare<std::vector<
|
||||
std::string> >("state_interfaces", state_interface_types_);
|
||||
} catch (const std::exception &e) {
|
||||
fprintf(stderr, "Exception thrown during init stage with message: %s \n", e.what());
|
||||
return controller_interface::CallbackReturn::ERROR;
|
||||
}
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
controller_interface::InterfaceConfiguration LegPdController::command_interface_configuration() const {
|
||||
controller_interface::InterfaceConfiguration conf = {config_type::INDIVIDUAL, {}};
|
||||
|
||||
conf.names.reserve(joint_names_.size());
|
||||
for (const auto &joint_name: joint_names_) {
|
||||
conf.names.push_back(joint_name + "/effort");
|
||||
}
|
||||
|
||||
return conf;
|
||||
}
|
||||
|
||||
controller_interface::InterfaceConfiguration LegPdController::state_interface_configuration() const {
|
||||
controller_interface::InterfaceConfiguration conf = {config_type::INDIVIDUAL, {}};
|
||||
conf.names.reserve(joint_names_.size() * state_interface_types_.size());
|
||||
for (const auto &joint_name: joint_names_) {
|
||||
for (const auto &interface_type: state_interface_types_) {
|
||||
conf.names.push_back(joint_name + "/" += interface_type);
|
||||
}
|
||||
}
|
||||
return conf;
|
||||
}
|
||||
|
||||
controller_interface::CallbackReturn LegPdController::on_configure(
|
||||
const rclcpp_lifecycle::State & /*previous_state*/) {
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
controller_interface::CallbackReturn LegPdController::on_activate(
|
||||
const rclcpp_lifecycle::State & /*previous_state*/) {
|
||||
// assign effort command interface
|
||||
for (auto &interface: command_interfaces_) {
|
||||
joint_effort_command_interface_.emplace_back(interface);
|
||||
}
|
||||
|
||||
// assign state interfaces
|
||||
for (auto &interface: state_interfaces_) {
|
||||
state_interface_map_[interface.get_interface_name()]->push_back(interface);
|
||||
}
|
||||
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
controller_interface::CallbackReturn LegPdController::on_deactivate(
|
||||
const rclcpp_lifecycle::State & /*previous_state*/) {
|
||||
release_interfaces();
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
bool LegPdController::on_set_chained_mode(bool /*chained_mode*/) {
|
||||
return true;
|
||||
}
|
||||
|
||||
controller_interface::return_type LegPdController::update_and_write_commands(
|
||||
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
|
||||
for (size_t i = 0; i < joint_names_.size(); ++i) {
|
||||
// PD Controller
|
||||
const double torque = joint_effort_command_[i] + joint_kp_command_[i] * (
|
||||
joint_position_command_[i] - joint_position_state_interface_[i].get().get_value())
|
||||
+
|
||||
joint_kd_command_[i] * (
|
||||
joint_velocities_command_[i] - joint_velocity_state_interface_[i].get().
|
||||
get_value());
|
||||
joint_effort_command_interface_[i].get().set_value(torque);
|
||||
}
|
||||
|
||||
return controller_interface::return_type::OK;
|
||||
}
|
||||
|
||||
std::vector<hardware_interface::CommandInterface> LegPdController::on_export_reference_interfaces() {
|
||||
std::vector<hardware_interface::CommandInterface> reference_interfaces;
|
||||
|
||||
int ind = 0;
|
||||
std::string controller_name = get_node()->get_name();
|
||||
for (const auto &joint_name: joint_names_) {
|
||||
reference_interfaces.emplace_back(controller_name, joint_name + "/position", &joint_position_command_[ind]);
|
||||
reference_interfaces.emplace_back(controller_name, joint_name + "/velocity",
|
||||
&joint_velocities_command_[ind]);
|
||||
reference_interfaces.emplace_back(controller_name, joint_name + "/torque", &joint_effort_command_[ind]);
|
||||
reference_interfaces.emplace_back(controller_name, joint_name + "/kp", &joint_kp_command_[ind]);
|
||||
reference_interfaces.emplace_back(controller_name, joint_name + "/kd", &joint_kd_command_[ind]);
|
||||
ind++;
|
||||
}
|
||||
|
||||
return reference_interfaces;
|
||||
}
|
||||
|
||||
controller_interface::return_type LegPdController::update_reference_from_subscribers(
|
||||
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
|
||||
return controller_interface::return_type::OK;
|
||||
}
|
||||
}
|
||||
|
||||
#include <pluginlib/class_list_macros.hpp>
|
||||
PLUGINLIB_EXPORT_CLASS(leg_pd_controller::LegPdController, controller_interface::ChainableControllerInterface);
|
|
@ -89,7 +89,7 @@ namespace unitree_guide_controller {
|
|||
std::unordered_map<
|
||||
std::string, std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> > *>
|
||||
command_interface_map_ = {
|
||||
{"effort", &ctrl_comp_.joint_effort_command_interface_},
|
||||
{"torque", &ctrl_comp_.joint_torque_command_interface_},
|
||||
{"position", &ctrl_comp_.joint_position_command_interface_},
|
||||
{"velocity", &ctrl_comp_.joint_velocity_command_interface_},
|
||||
{"kp", &ctrl_comp_.joint_kp_command_interface_},
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
struct CtrlComponent {
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> >
|
||||
joint_effort_command_interface_;
|
||||
joint_torque_command_interface_;
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> >
|
||||
joint_position_command_interface_;
|
||||
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface> >
|
||||
|
@ -54,7 +54,7 @@ struct CtrlComponent {
|
|||
}
|
||||
|
||||
void clear() {
|
||||
joint_effort_command_interface_.clear();
|
||||
joint_torque_command_interface_.clear();
|
||||
joint_position_command_interface_.clear();
|
||||
joint_velocity_command_interface_.clear();
|
||||
joint_kd_command_interface_.clear();
|
||||
|
|
|
@ -89,7 +89,7 @@ void StateBalanceTest::calcTorque() {
|
|||
for (int i = 0; i < 4; i++) {
|
||||
KDL::JntArray torque = robot_model_.getTorque(force_feet_body.col(i), i);
|
||||
for (int j = 0; j < 3; j++) {
|
||||
ctrl_comp_.joint_effort_command_interface_[i * 3 + j].get().set_value(torque(j));
|
||||
ctrl_comp_.joint_torque_command_interface_[i * 3 + j].get().set_value(torque(j));
|
||||
ctrl_comp_.joint_position_command_interface_[i * 3 + j].get().set_value(current_joints[i](j));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -25,7 +25,7 @@ void StateFixedDown::run() {
|
|||
ctrl_comp_.joint_position_command_interface_[i].get().set_value(
|
||||
phase * target_pos_[i] + (1 - phase) * start_pos_[i]);
|
||||
ctrl_comp_.joint_velocity_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_effort_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_torque_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_kp_command_interface_[i].get().set_value(50.0);
|
||||
ctrl_comp_.joint_kd_command_interface_[i].get().set_value(3.5);
|
||||
}
|
||||
|
|
|
@ -25,7 +25,7 @@ void StateFixedStand::run() {
|
|||
ctrl_comp_.joint_position_command_interface_[i].get().set_value(
|
||||
phase * target_pos_[i] + (1 - phase) * start_pos_[i]);
|
||||
ctrl_comp_.joint_velocity_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_effort_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_torque_command_interface_[i].get().set_value(0);
|
||||
ctrl_comp_.joint_kp_command_interface_[i].get().set_value(
|
||||
phase * 60.0 + (1 - phase) * 20.0);
|
||||
ctrl_comp_.joint_kd_command_interface_[i].get().set_value(3.5);
|
||||
|
|
|
@ -12,7 +12,7 @@ StatePassive::StatePassive(CtrlComponent &ctrlComp) : FSMState(
|
|||
}
|
||||
|
||||
void StatePassive::enter() {
|
||||
for (auto i: ctrl_comp_.joint_effort_command_interface_) {
|
||||
for (auto i: ctrl_comp_.joint_torque_command_interface_) {
|
||||
i.get().set_value(0);
|
||||
}
|
||||
for (auto i: ctrl_comp_.joint_position_command_interface_) {
|
||||
|
|
|
@ -99,6 +99,6 @@ void StateSwingTest::torqueCtrl() const {
|
|||
KDL::JntArray torque0 = robot_model_.getTorque(force0, 0);
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
ctrl_comp_.joint_effort_command_interface_[i].get().set_value(torque0(i));
|
||||
ctrl_comp_.joint_torque_command_interface_[i].get().set_value(torque0(i));
|
||||
}
|
||||
}
|
||||
|
|
|
@ -150,7 +150,7 @@ void StateTrotting::calcTau() {
|
|||
for (int i = 0; i < 4; i++) {
|
||||
KDL::JntArray torque = robot_model_.getTorque(force_feet_body_.col(i), i);
|
||||
for (int j = 0; j < 3; j++) {
|
||||
ctrl_comp_.joint_effort_command_interface_[i * 3 + j].get().set_value(torque(j));
|
||||
ctrl_comp_.joint_torque_command_interface_[i * 3 + j].get().set_value(torque(j));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -138,6 +138,7 @@ namespace unitree_guide_controller {
|
|||
}
|
||||
}
|
||||
|
||||
// Create FSM List
|
||||
state_list_.passive = std::make_shared<StatePassive>(ctrl_comp_);
|
||||
state_list_.fixedDown = std::make_shared<StateFixedDown>(ctrl_comp_);
|
||||
state_list_.fixedStand = std::make_shared<StateFixedStand>(ctrl_comp_);
|
||||
|
|
|
@ -36,7 +36,7 @@ unitree_guide_controller:
|
|||
- RL_calf_joint
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
- torque
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
<joint name="FR_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -22,7 +22,7 @@
|
|||
<joint name="FR_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -34,7 +34,7 @@
|
|||
<joint name="FR_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -46,7 +46,7 @@
|
|||
<joint name="FL_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -58,7 +58,7 @@
|
|||
<joint name="FL_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -70,7 +70,7 @@
|
|||
<joint name="FL_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -82,7 +82,7 @@
|
|||
<joint name="RR_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -94,7 +94,7 @@
|
|||
<joint name="RR_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -106,7 +106,7 @@
|
|||
<joint name="RR_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -118,7 +118,7 @@
|
|||
<joint name="RL_hip_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -130,7 +130,7 @@
|
|||
<joint name="RL_thigh_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
@ -142,7 +142,7 @@
|
|||
<joint name="RL_calf_joint">
|
||||
<command_interface name="position"/>
|
||||
<command_interface name="velocity"/>
|
||||
<command_interface name="effort"/>
|
||||
<command_interface name="torque"/>
|
||||
<command_interface name="kp"/>
|
||||
<command_interface name="kd"/>
|
||||
|
||||
|
|
|
@ -1,8 +1,7 @@
|
|||
# Controller Manager configuration
|
||||
controller_manager:
|
||||
ros__parameters:
|
||||
update_rate: 1000 # Hz
|
||||
use_sim_time: true # If running in simulation
|
||||
update_rate: 500 # Hz
|
||||
|
||||
# Define the available controllers
|
||||
joint_state_broadcaster:
|
||||
|
@ -11,7 +10,76 @@ controller_manager:
|
|||
imu_sensor_broadcaster:
|
||||
type: imu_sensor_broadcaster/IMUSensorBroadcaster
|
||||
|
||||
leg_pd_controller:
|
||||
type: leg_pd_controller/LegPdController
|
||||
|
||||
imu_sensor_broadcaster:
|
||||
ros__parameters:
|
||||
sensor_name: "imu_sensor"
|
||||
frame_id: "imu_sensor"
|
||||
|
||||
leg_pd_controller:
|
||||
ros__parameters:
|
||||
update_rate: 500 # Hz
|
||||
joints:
|
||||
- RF_HAA
|
||||
- RH_HFE
|
||||
- RF_KFE
|
||||
- LF_HAA
|
||||
- LF_HFE
|
||||
- LF_KFE
|
||||
- RH_HAA
|
||||
- RH_HFE
|
||||
- RH_KFE
|
||||
- LH_HAA
|
||||
- LH_HFE
|
||||
- LH_KFE
|
||||
|
||||
command_interfaces:
|
||||
- effort
|
||||
|
||||
state_interfaces:
|
||||
- position
|
||||
- velocity
|
||||
|
||||
unitree_guide_controller:
|
||||
ros__parameters:
|
||||
joints:
|
||||
- RF_HAA
|
||||
- RH_HFE
|
||||
- RF_KFE
|
||||
- LF_HAA
|
||||
- LF_HFE
|
||||
- LF_KFE
|
||||
- RH_HAA
|
||||
- RH_HFE
|
||||
- RH_KFE
|
||||
- LH_HAA
|
||||
- LH_HFE
|
||||
- LH_KFE
|
||||
|
||||
command_interfaces:
|
||||
- torque
|
||||
- position
|
||||
- velocity
|
||||
- kp
|
||||
- kd
|
||||
|
||||
state_interfaces:
|
||||
- effort
|
||||
- position
|
||||
- velocity
|
||||
|
||||
imu_name: "imu_sensor"
|
||||
|
||||
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
|
|
@ -10,7 +10,7 @@ Panels:
|
|||
- /RobotModel1
|
||||
- /RobotModel1/Description Topic1
|
||||
Splitter Ratio: 0.5
|
||||
Tree Height: 543
|
||||
Tree Height: 301
|
||||
- Class: rviz_common/Selection
|
||||
Name: Selection
|
||||
- Class: rviz_common/Tool Properties
|
||||
|
@ -235,10 +235,10 @@ Visualization Manager:
|
|||
Window Geometry:
|
||||
Displays:
|
||||
collapsed: false
|
||||
Height: 1061
|
||||
Height: 555
|
||||
Hide Left Dock: false
|
||||
Hide Right Dock: false
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001f40000031bfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b000000b200fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000700000031b0000018600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000031bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000031b0000013800fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000065a0000005efc0100000002fb0000000800540069006d006501000000000000065a0000047a00fffffffb0000000800540069006d006501000000000000045000000000000000000000065a0000031b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd0000000400000000000001f40000031bfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007300000000700000031b000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000015d0000031bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000700000031b000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000002e50000005efc0100000002fb0000000800540069006d00650100000000000002e50000026f00fffffffb0000000800540069006d00650100000000000004500000000000000000000002e50000016900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
|
@ -247,6 +247,6 @@ Window Geometry:
|
|||
collapsed: false
|
||||
Views:
|
||||
collapsed: false
|
||||
Width: 1626
|
||||
X: 787
|
||||
Y: 356
|
||||
Width: 741
|
||||
X: 773
|
||||
Y: 267
|
||||
|
|
|
@ -3,9 +3,10 @@ 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
|
||||
from launch.actions import DeclareLaunchArgument, OpaqueFunction, IncludeLaunchDescription, RegisterEventHandler
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import PathJoinSubstitution
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch_ros.actions import Node
|
||||
from launch_ros.substitutions import FindPackageShare
|
||||
|
||||
|
@ -29,33 +30,59 @@ def launch_setup(context, *args, **kwargs):
|
|||
arguments=['-topic', 'robot_description', '-name',
|
||||
robot_type, '-allow_renaming', 'true', '-z', '0.5'],
|
||||
)
|
||||
return [
|
||||
Node(
|
||||
|
||||
robot_state_publisher = Node(
|
||||
package='robot_state_publisher',
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
parameters=[
|
||||
{
|
||||
'use_sim_time': True,
|
||||
'publish_frequency': 100.0,
|
||||
'publish_frequency': 20.0,
|
||||
'use_tf_static': True,
|
||||
'robot_description': robot_description
|
||||
'robot_description': robot_description,
|
||||
'ignore_timestamp': True
|
||||
}
|
||||
],
|
||||
),
|
||||
Node(
|
||||
)
|
||||
|
||||
joint_state_publisher = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["joint_state_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
),
|
||||
Node(
|
||||
)
|
||||
|
||||
imu_sensor_broadcaster = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["imu_sensor_broadcaster",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
),
|
||||
)
|
||||
|
||||
leg_pd_controller = Node(
|
||||
package="controller_manager",
|
||||
executable="spawner",
|
||||
arguments=["leg_pd_controller",
|
||||
"--controller-manager", "/controller_manager"],
|
||||
)
|
||||
|
||||
|
||||
return [
|
||||
robot_state_publisher,
|
||||
gz_spawn_entity,
|
||||
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=[leg_pd_controller],
|
||||
)
|
||||
),
|
||||
]
|
||||
|
||||
|
||||
|
|
|
@ -14,27 +14,6 @@
|
|||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LF_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RH_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LH_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RF_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
|
@ -42,27 +21,6 @@
|
|||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LF_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RH_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LH_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RF_KFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
|
@ -70,6 +28,20 @@
|
|||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LF_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LF_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LF_KFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
|
@ -77,6 +49,20 @@
|
|||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RH_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RH_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="RH_KFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
|
@ -84,6 +70,20 @@
|
|||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LH_HAA">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LH_HFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
<state_interface name="velocity"/>
|
||||
<state_interface name="effort"/>
|
||||
</joint>
|
||||
|
||||
<joint name="LH_KFE">
|
||||
<command_interface name="effort" initial_value="0.0"/>
|
||||
<state_interface name="position"/>
|
||||
|
|
|
@ -26,7 +26,7 @@ public:
|
|||
hardware_interface::return_type write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) override;
|
||||
|
||||
protected:
|
||||
std::vector<double> joint_effort_command_;
|
||||
std::vector<double> joint_torque_command_;
|
||||
std::vector<double> joint_position_command_;
|
||||
std::vector<double> joint_velocities_command_;
|
||||
std::vector<double> joint_kp_command_;
|
||||
|
|
|
@ -18,7 +18,7 @@ rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn Hardwa
|
|||
return CallbackReturn::ERROR;
|
||||
}
|
||||
|
||||
joint_effort_command_.assign(12, 0);
|
||||
joint_torque_command_.assign(12, 0);
|
||||
joint_position_command_.assign(12, 0);
|
||||
joint_velocities_command_.assign(12, 0);
|
||||
joint_kp_command_.assign(12, 0);
|
||||
|
@ -100,7 +100,7 @@ std::vector<hardware_interface::CommandInterface> HardwareUnitree::export_comman
|
|||
|
||||
ind = 0;
|
||||
for (const auto &joint_name: joint_interfaces["effort"]) {
|
||||
command_interfaces.emplace_back(joint_name, "effort", &joint_effort_command_[ind]);
|
||||
command_interfaces.emplace_back(joint_name, "torque", &joint_torque_command_[ind]);
|
||||
command_interfaces.emplace_back(joint_name, "kp", &joint_kp_command_[ind]);
|
||||
command_interfaces.emplace_back(joint_name, "kd", &joint_kd_command_[ind]);
|
||||
ind++;
|
||||
|
@ -108,7 +108,7 @@ std::vector<hardware_interface::CommandInterface> HardwareUnitree::export_comman
|
|||
return command_interfaces;
|
||||
}
|
||||
|
||||
return_type HardwareUnitree::read(const rclcpp::Time &time, const rclcpp::Duration &period) {
|
||||
return_type HardwareUnitree::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
|
||||
// joint states
|
||||
for (int i(0); i < 12; ++i) {
|
||||
joint_position_[i] = low_state_.motor_state()[i].q();
|
||||
|
@ -131,7 +131,7 @@ return_type HardwareUnitree::read(const rclcpp::Time &time, const rclcpp::Durati
|
|||
return return_type::OK;
|
||||
}
|
||||
|
||||
return_type HardwareUnitree::write(const rclcpp::Time &, const rclcpp::Duration &) {
|
||||
return_type HardwareUnitree::write(const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/) {
|
||||
// send command
|
||||
for (int i(0); i < 12; ++i) {
|
||||
low_cmd_.motor_cmd()[i].mode() = 0x01;
|
||||
|
@ -139,7 +139,7 @@ return_type HardwareUnitree::write(const rclcpp::Time &, const rclcpp::Duration
|
|||
low_cmd_.motor_cmd()[i].dq() = static_cast<float>(joint_velocities_command_[i]);
|
||||
low_cmd_.motor_cmd()[i].kp() = static_cast<float>(joint_kp_command_[i]);
|
||||
low_cmd_.motor_cmd()[i].kd() = static_cast<float>(joint_kd_command_[i]);
|
||||
low_cmd_.motor_cmd()[i].tau() = static_cast<float>(joint_effort_command_[i]);
|
||||
low_cmd_.motor_cmd()[i].tau() = static_cast<float>(joint_torque_command_[i]);
|
||||
}
|
||||
|
||||
low_cmd_.crc() = crc32_core(reinterpret_cast<uint32_t *>(&low_cmd_),
|
||||
|
|
Loading…
Reference in New Issue