Skip to content

Commit

Permalink
ported to humble
Browse files Browse the repository at this point in the history
  • Loading branch information
Maciej Bednarczyk committed Nov 4, 2022
1 parent 050cb9c commit cdbbc8d
Show file tree
Hide file tree
Showing 11 changed files with 97 additions and 92 deletions.
10 changes: 5 additions & 5 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,28 +19,28 @@ jobs:
- name: Build Docker Image
uses: docker/build-push-action@v2
with:
tags: franka_ros2:galactic
tags: franka_ros2:humble
file: Dockerfile
push: false

- name: Build
uses: addnab/docker-run-action@v3
with:
image: franka_ros2:galactic
image: franka_ros2:humble
options: -v ${{github.workspace}}/:/ros/
run: |
cd /ros
. /opt/ros/galactic/setup.sh
. /opt/ros/humble/setup.sh
colcon build --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCHECK_TIDY=ON
- name: Test
uses: addnab/docker-run-action@v3
with:
image: franka_ros2:galactic
image: franka_ros2:humble
options: -v ${{github.workspace}}/:/ros/
run: |
cd /ros
. /opt/ros/galactic/setup.sh
. /opt/ros/humble/setup.sh
. install/setup.sh
colcon test
colcon test-result
Expand Down
22 changes: 11 additions & 11 deletions Dockerfile
Original file line number Diff line number Diff line change
@@ -1,21 +1,21 @@
FROM ros:galactic
FROM ros:humble
RUN apt-get update -y && apt-get install -y --allow-unauthenticated \
clang-6.0 \
clang-format-6.0 \
clang-tidy-6.0 \
python3-pip \
libpoco-dev \
libeigen3-dev \
ros-galactic-control-msgs \
ros-galactic-xacro \
ros-galactic-ament-cmake-clang-format \
ros-galactic-ament-clang-format \
ros-galactic-ament-flake8 \
ros-galactic-ament-cmake-clang-tidy \
ros-galactic-angles \
ros-galactic-ros2-control \
ros-galactic-realtime-tools \
ros-galactic-control-toolbox \
ros-humble-control-msgs \
ros-humble-xacro \
ros-humble-ament-cmake-clang-format \
ros-humble-ament-clang-format \
ros-humble-ament-flake8 \
ros-humble-ament-cmake-clang-tidy \
ros-humble-angles \
ros-humble-ros2-control \
ros-humble-realtime-tools \
ros-humble-control-toolbox \
&& rm -rf /var/lib/apt/lists/*

RUN python3 -m pip install -U \
Expand Down
4 changes: 2 additions & 2 deletions Jenkinsfile
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,15 @@ pipeline {
stage('Build') {
steps {
sh '''
. /opt/ros/galactic/setup.sh
. /opt/ros/humble/setup.sh
colcon build --cmake-args -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -DCHECK_TIDY=ON
'''
}
}
stage('Test') {
steps {
sh '''
. /opt/ros/galactic/setup.sh
. /opt/ros/humble/setup.sh
. install/setup.sh
colcon test
colcon test-result
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ controller_interface::return_type GravityCompensationExampleController::update(

CallbackReturn GravityCompensationExampleController::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
arm_id_ = node_->get_parameter("arm_id").as_string();
arm_id_ = get_node()->get_parameter("arm_id").as_string();
return CallbackReturn::SUCCESS;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ controller_interface::return_type JointImpedanceExampleController::update(
const rclcpp::Duration& /*period*/) {
updateJointStates();
Vector7d q_goal = initial_q_;
auto time = this->node_->now() - start_time_;
auto time = this->get_node()->now() - start_time_;
double delta_angle = M_PI / 8.0 * (1 - std::cos(M_PI / 2.5 * time.seconds()));
q_goal(3) += delta_angle;
q_goal(4) += delta_angle;
Expand Down Expand Up @@ -79,25 +79,25 @@ CallbackReturn JointImpedanceExampleController::on_init() {

CallbackReturn JointImpedanceExampleController::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
arm_id_ = node_->get_parameter("arm_id").as_string();
auto k_gains = node_->get_parameter("k_gains").as_double_array();
auto d_gains = node_->get_parameter("d_gains").as_double_array();
arm_id_ = get_node()->get_parameter("arm_id").as_string();
auto k_gains = get_node()->get_parameter("k_gains").as_double_array();
auto d_gains = get_node()->get_parameter("d_gains").as_double_array();
if (k_gains.empty()) {
RCLCPP_FATAL(node_->get_logger(), "k_gains parameter not set");
RCLCPP_FATAL(get_node()->get_logger(), "k_gains parameter not set");
return CallbackReturn::FAILURE;
}
if (k_gains.size() != static_cast<uint>(num_joints)) {
RCLCPP_FATAL(node_->get_logger(), "k_gains should be of size %d but is of size %ld", num_joints,
k_gains.size());
RCLCPP_FATAL(get_node()->get_logger(), "k_gains should be of size %d but is of size %ld",
num_joints, k_gains.size());
return CallbackReturn::FAILURE;
}
if (d_gains.empty()) {
RCLCPP_FATAL(node_->get_logger(), "d_gains parameter not set");
RCLCPP_FATAL(get_node()->get_logger(), "d_gains parameter not set");
return CallbackReturn::FAILURE;
}
if (d_gains.size() != static_cast<uint>(num_joints)) {
RCLCPP_FATAL(node_->get_logger(), "d_gains should be of size %d but is of size %ld", num_joints,
d_gains.size());
RCLCPP_FATAL(get_node()->get_logger(), "d_gains should be of size %d but is of size %ld",
num_joints, d_gains.size());
return CallbackReturn::FAILURE;
}
for (int i = 0; i < num_joints; ++i) {
Expand All @@ -112,7 +112,7 @@ CallbackReturn JointImpedanceExampleController::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
updateJointStates();
initial_q_ = q_;
start_time_ = this->node_->now();
start_time_ = this->get_node()->now();
return CallbackReturn::SUCCESS;
}

Expand Down
22 changes: 11 additions & 11 deletions franka_example_controllers/src/move_to_start_example_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ controller_interface::return_type MoveToStartExampleController::update(
const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/) {
updateJointStates();
auto trajectory_time = this->node_->now() - start_time_;
auto trajectory_time = this->get_node()->now() - start_time_;
auto motion_generator_output = motion_generator_->getDesiredJointPositions(trajectory_time);
Vector7d q_desired = motion_generator_output.first;
bool finished = motion_generator_output.second;
Expand Down Expand Up @@ -84,25 +84,25 @@ CallbackReturn MoveToStartExampleController::on_init() {

CallbackReturn MoveToStartExampleController::on_configure(
const rclcpp_lifecycle::State& /*previous_state*/) {
arm_id_ = node_->get_parameter("arm_id").as_string();
auto k_gains = node_->get_parameter("k_gains").as_double_array();
auto d_gains = node_->get_parameter("d_gains").as_double_array();
arm_id_ = get_node()->get_parameter("arm_id").as_string();
auto k_gains = get_node()->get_parameter("k_gains").as_double_array();
auto d_gains = get_node()->get_parameter("d_gains").as_double_array();
if (k_gains.empty()) {
RCLCPP_FATAL(node_->get_logger(), "k_gains parameter not set");
RCLCPP_FATAL(get_node()->get_logger(), "k_gains parameter not set");
return CallbackReturn::FAILURE;
}
if (k_gains.size() != static_cast<uint>(num_joints)) {
RCLCPP_FATAL(node_->get_logger(), "k_gains should be of size %d but is of size %ld", num_joints,
k_gains.size());
RCLCPP_FATAL(get_node()->get_logger(), "k_gains should be of size %d but is of size %ld",
num_joints, k_gains.size());
return CallbackReturn::FAILURE;
}
if (d_gains.empty()) {
RCLCPP_FATAL(node_->get_logger(), "d_gains parameter not set");
RCLCPP_FATAL(get_node()->get_logger(), "d_gains parameter not set");
return CallbackReturn::FAILURE;
}
if (d_gains.size() != static_cast<uint>(num_joints)) {
RCLCPP_FATAL(node_->get_logger(), "d_gains should be of size %d but is of size %ld", num_joints,
d_gains.size());
RCLCPP_FATAL(get_node()->get_logger(), "d_gains should be of size %d but is of size %ld",
num_joints, d_gains.size());
return CallbackReturn::FAILURE;
}
for (int i = 0; i < num_joints; ++i) {
Expand All @@ -117,7 +117,7 @@ CallbackReturn MoveToStartExampleController::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
updateJointStates();
motion_generator_ = std::make_unique<MotionGenerator>(0.2, q_, q_goal_);
start_time_ = this->node_->now();
start_time_ = this->get_node()->now();
return CallbackReturn::SUCCESS;
}

Expand Down
4 changes: 2 additions & 2 deletions franka_gripper/src/gripper_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,11 @@
namespace franka_gripper {
GripperActionServer::GripperActionServer(const rclcpp::NodeOptions& options)
: Node("franka_gripper_node", options) {
this->declare_parameter("robot_ip");
this->declare_parameter("robot_ip", std::string());
this->declare_parameter("default_grasp_epsilon.inner", k_default_grasp_epsilon);
this->declare_parameter("default_grasp_epsilon.outer", k_default_grasp_epsilon);
this->declare_parameter("default_speed", k_default_speed);
this->declare_parameter("joint_names");
this->declare_parameter("joint_names", std::vector<std::string>());
this->declare_parameter("state_publish_rate", k_default_state_publish_rate);
this->declare_parameter("feedback_publish_rate", k_default_feedback_publish_rate);
std::string robot_ip;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,10 @@ class FrankaHardwareInterface : public hardware_interface::SystemInterface {
std::vector<hardware_interface::CommandInterface> export_command_interfaces() override;
CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
hardware_interface::return_type read() override;
hardware_interface::return_type write() override;
hardware_interface::return_type read(const rclcpp::Time& time,
const rclcpp::Duration& period) override;
hardware_interface::return_type write(const rclcpp::Time& time,
const rclcpp::Duration& period) override;
CallbackReturn on_init(const hardware_interface::HardwareInfo& info) override;
static const size_t kNumberOfJoints = 7;

Expand Down
9 changes: 6 additions & 3 deletions franka_hardware/src/franka_hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ CallbackReturn FrankaHardwareInterface::on_activate(
const rclcpp_lifecycle::State& /*previous_state*/) {
robot_->initializeContinuousReading();
hw_commands_.fill(0);
read(); // makes sure that the robot state is properly initialized.
read(rclcpp::Time(0),
rclcpp::Duration(0, 0)); // makes sure that the robot state is properly initialized.
RCLCPP_INFO(getLogger(), "Started");
return CallbackReturn::SUCCESS;
}
Expand All @@ -72,15 +73,17 @@ CallbackReturn FrankaHardwareInterface::on_deactivate(
return CallbackReturn::SUCCESS;
}

hardware_interface::return_type FrankaHardwareInterface::read() {
hardware_interface::return_type FrankaHardwareInterface::read(const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/) {
const auto kState = robot_->read();
hw_positions_ = kState.q;
hw_velocities_ = kState.dq;
hw_efforts_ = kState.tau_J;
return hardware_interface::return_type::OK;
}

hardware_interface::return_type FrankaHardwareInterface::write() {
hardware_interface::return_type FrankaHardwareInterface::write(const rclcpp::Time& /*time*/,
const rclcpp::Duration& /*period*/) {
if (std::any_of(hw_commands_.begin(), hw_commands_.end(),
[](double c) { return not std::isfinite(c); })) {
return hardware_interface::return_type::ERROR;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ struct SegmentTolerances
* \return Trajectory segment tolerances.
*/
SegmentTolerances get_segment_tolerances(
const rclcpp::Node & node, const std::vector<std::string> & joint_names)
const rclcpp_lifecycle::LifecycleNode & node, const std::vector<std::string> & joint_names)
{
const auto n_joints = joint_names.size();
SegmentTolerances tolerances;
Expand Down
Loading

0 comments on commit cdbbc8d

Please sign in to comment.