Skip to content

Commit

Permalink
Apply pre-commit
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Aug 1, 2023
1 parent 66cbbea commit 0c8b6bd
Show file tree
Hide file tree
Showing 8 changed files with 128 additions and 8 deletions.
19 changes: 18 additions & 1 deletion r6bot/hardware_driver/include/r6bot_hardware/r6bot_hardware.hpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,19 @@
#pragma once
// Copyright 2023 ros2_control Development Team
//
// 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.

#ifndef R6BOT_HARDWARE__R6BOT_HARDWARE_HPP_
#define R6BOT_HARDWARE__R6BOT_HARDWARE_HPP_

#include "string"
#include "unordered_map"
Expand Down Expand Up @@ -43,3 +58,5 @@ class HARDWARE_INTERFACE_PUBLIC RobotSystem : public hardware_interface::SystemI
};

} // namespace r6bot_hardware

#endif // R6BOT_HARDWARE__R6BOT_HARDWARE_HPP_
16 changes: 15 additions & 1 deletion r6bot/hardware_driver/src/r6bot_hardware.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
// Copyright 2023 ros2_control Development Team
//
// 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.

#include "r6bot_hardware/r6bot_hardware.hpp"
#include <string>
#include <vector>
Expand Down Expand Up @@ -86,7 +100,7 @@ std::vector<hardware_interface::CommandInterface> RobotSystem::export_command_in

return_type RobotSystem::read(const rclcpp::Time & /*time*/, const rclcpp::Duration & period)
{
// TODO set sensor_states_ values from subscriber
// TODO(pac48) set sensor_states_ values from subscriber

for (auto i = 0ul; i < joint_velocities_command_.size(); i++)
{
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,25 @@
#pragma once
// Copyright 2023 ros2_control Development Team
//
// 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.

#ifndef R6BOT_CONTROLLER__R6BOT_CONTROLLER_HPP_
#define R6BOT_CONTROLLER__R6BOT_CONTROLLER_HPP_

#include <chrono>
#include <memory>
#include <mutex>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

Expand Down Expand Up @@ -102,3 +118,5 @@ class RobotController : public controller_interface::ControllerInterface
};

} // namespace r6bot_controller

#endif // R6BOT_CONTROLLER__R6BOT_CONTROLLER_HPP_
14 changes: 14 additions & 0 deletions r6bot/r6bot_controller/launch/r6bot_controller.launch.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
# Copyright 2023 ros2_control Development Team
#
# 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.

from launch import LaunchDescription
from launch.actions import RegisterEventHandler
from launch.event_handlers import OnProcessExit
Expand Down
19 changes: 17 additions & 2 deletions r6bot/r6bot_controller/src/r6bot_controller.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
// Copyright 2023 ros2_control Development Team
//
// 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.

#include "r6bot_controller/r6bot_controller.hpp"

#include <stddef.h>
Expand Down Expand Up @@ -66,7 +80,8 @@ controller_interface::InterfaceConfiguration RobotController::state_interface_co
controller_interface::CallbackReturn RobotController::on_configure(const rclcpp_lifecycle::State &)
{
auto callback =
[this](const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg) -> void {
[this](const std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg) -> void
{
traj_msg_external_point_ptr_.writeFromNonRT(traj_msg);
new_msg_ = true;
};
Expand Down Expand Up @@ -126,7 +141,7 @@ void interpolate_trajectory_point(
double total_time = last_time.sec + last_time.nanosec * 1E-9;

size_t ind = cur_time.seconds() * (traj_len / total_time);
ind = std::min(ind, (size_t)traj_len - 2);
ind = std::min(ind, static_cast<double>(traj_len) - 2);
double delta = cur_time.seconds() - ind * (total_time / traj_len);
interpolate_point(traj_msg.points[ind], traj_msg.points[ind + 1], point_interp, delta);
}
Expand Down
14 changes: 14 additions & 0 deletions r6bot/r6bot_description/launch/view_r6bot.launch.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
# Copyright 2023 ros2_control Development Team
#
# 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.

from launch import LaunchDescription
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.actions import Node
Expand Down
14 changes: 14 additions & 0 deletions r6bot/reference_generator/launch/send_trajectory.launch.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
# Copyright 2023 ros2_control Development Team
#
# 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.

from launch import LaunchDescription
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.actions import Node
Expand Down
20 changes: 17 additions & 3 deletions r6bot/reference_generator/src/send_trajectory.cpp
Original file line number Diff line number Diff line change
@@ -1,3 +1,17 @@
// Copyright 2023 ros2_control Development Team
//
// 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.

#include <kdl/chainfksolverpos_recursive.hpp>
#include <kdl/chainiksolvervel_pinv.hpp>
#include <kdl/jntarray.hpp>
Expand Down Expand Up @@ -30,7 +44,6 @@ int main(int argc, char ** argv)
auto joint_velocities = KDL::JntArray(chain.getNrOfJoints());
auto twist = KDL::Twist();
// create KDL solvers
auto fk_pos_solver_ = std::make_shared<KDL::ChainFkSolverPos_recursive>(chain);
auto ik_vel_solver_ = std::make_shared<KDL::ChainIkSolverVel_pinv>(chain, 0.0000001);

trajectory_msgs::msg::JointTrajectory trajectory_msg;
Expand Down Expand Up @@ -76,8 +89,9 @@ int main(int argc, char ** argv)

// set timing information
trajectory_point_msg.time_from_start.sec = i / loop_rate;
trajectory_point_msg.time_from_start.nanosec =
1E9 / loop_rate * (double)(i - loop_rate * (i / loop_rate));
trajectory_point_msg.time_from_start.nanosec = static_cast<int>(
1E9 / loop_rate *
static_cast<double>(t - loop_rate * (i / loop_rate))); // implicit integer division

trajectory_msg.points.push_back(trajectory_point_msg);
}
Expand Down

0 comments on commit 0c8b6bd

Please sign in to comment.