Bioscara
DALSA's DIY SCARA Robot Arm.
Loading...
Searching...
No Matches
arm_hardware.hpp
Go to the documentation of this file.
1// Copyright 2023 ros2_control Development Team
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef ARM_HARDWARE_HPP_
16#define ARM_HARDWARE_HPP_
17
18#include <memory>
19#include <string>
20#include <vector>
21#include <set>
22#include <unordered_map>
23#include <memory>
24#include <mutex>
25
28
29#include "hardware_interface/handle.hpp"
30#include "hardware_interface/hardware_info.hpp"
31#include "hardware_interface/system_interface.hpp"
32#include "hardware_interface/types/hardware_interface_return_values.hpp"
33#include "rclcpp/macros.hpp"
34#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
35#include "rclcpp_lifecycle/state.hpp"
36
38{
39 constexpr char HW_IF_HOME[] = "home";
40
54 class BioscaraArmHardwareInterface : public hardware_interface::SystemInterface
55 {
56 public:
57 RCLCPP_SHARED_PTR_DEFINITIONS(BioscaraArmHardwareInterface)
58
59
88 hardware_interface::CallbackReturn on_init(
89 const hardware_interface::HardwareComponentInterfaceParams &params) override;
90
100 hardware_interface::CallbackReturn on_shutdown(
101 const rclcpp_lifecycle::State &previous_state) override;
102
110 hardware_interface::CallbackReturn on_configure(
111 const rclcpp_lifecycle::State &previous_state) override;
112
121 hardware_interface::CallbackReturn on_cleanup(
122 const rclcpp_lifecycle::State &previous_state) override;
123
138 hardware_interface::CallbackReturn on_activate(
139 const rclcpp_lifecycle::State &previous_state) override;
140
149 hardware_interface::CallbackReturn on_deactivate(
150 const rclcpp_lifecycle::State &previous_state) override;
151
172 hardware_interface::return_type read(
173 const rclcpp::Time &time,
174 const rclcpp::Duration &period) override;
175
197 hardware_interface::return_type write(
198 const rclcpp::Time &time,
199 const rclcpp::Duration &period) override;
200
234 hardware_interface::return_type prepare_command_mode_switch(
235 const std::vector<std::string> &start_interfaces,
236 const std::vector<std::string> &stop_interfaces) override;
237
255 hardware_interface::return_type perform_command_mode_switch(
256 const std::vector<std::string> &start_interfaces,
257 const std::vector<std::string> &stop_interfaces) override;
258
286 hardware_interface::CallbackReturn on_error(
287 const rclcpp_lifecycle::State &previous_state) override;
288
289 private:
297 {
304 float speed;
305
311 u_int8_t threshold;
312
319 u_int8_t current;
320
328 float acceleration = 0.01;
329 };
330
338 {
345
360 float reduction = 1;
361
371 float min;
372
382 float max;
383
390
396 u_int8_t hold_current;
397
405
415
425
431 };
432
443 std::unordered_map<std::string, std::unique_ptr<bioscara_hardware_drivers::BaseJoint>> _joints;
444
452 std::unordered_map<std::string, joint_config_t> _joint_cfg;
453
467 std::unordered_map<std::string, std::set<std::string>> _joint_command_modes;
468
476 std::unordered_map<std::string, std::set<std::string>> _new_joint_command_modes;
477
493 std::vector<std::pair<std::string, hardware_interface::InterfaceDescription *>> _ordered_joint_state_interfaces_ptr;
494
508 std::mutex mtx;
509
518 bioscara_hardware_drivers::err_type_t start_homing(const std::string name, float velocity);
519
528
536 void split_interface_string_to_joint_and_name(std::string interface, std::string &joint_name, std::string &interface_name);
537
545
553 };
554
555} // namespace bioscara_hardware_interfaces
556
557#endif // ARM_HARDWARE_HPP_
The bioscara arm hardware interface class.
Definition arm_hardware.hpp:55
hardware_interface::return_type perform_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Perform the mode-switching for the new command interface combination in realtime context.
Definition arm_hardware.cpp:596
void split_interface_string_to_joint_and_name(std::string interface, std::string &joint_name, std::string &interface_name)
Split a interface string like "<joint_name>/<interface_name>" to "<joint_name>" and "<interface_name>...
Definition arm_hardware.cpp:712
hardware_interface::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &previous_state) override
Called on the transistion from the inactive to the unconfigured state.
Definition arm_hardware.cpp:251
std::unordered_map< std::string, std::set< std::string > > _new_joint_command_modes
Temporary cache of new joint_command_modes when switching controllers.
Definition arm_hardware.hpp:476
bioscara_hardware_drivers::err_type_t stop_homing(const std::string name)
wrapper method to stop homing.
Definition arm_hardware.cpp:696
std::unordered_map< std::string, joint_config_t > _joint_cfg
unordered map storing the configuration struct of the joints.
Definition arm_hardware.hpp:452
std::vector< std::pair< std::string, hardware_interface::InterfaceDescription * > > _ordered_joint_state_interfaces_ptr
A vector of a pair of interface name and pointer of the hardwares state interface which is ordered by...
Definition arm_hardware.hpp:493
hardware_interface::return_type prepare_command_mode_switch(const std::vector< std::string > &start_interfaces, const std::vector< std::string > &stop_interfaces) override
Performs checks and book keeping of the active control mode when changing controllers in non-realtime...
Definition arm_hardware.cpp:479
hardware_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State &previous_state) override
Called on the transistion from the unconfigured to the inactive state.
Definition arm_hardware.cpp:210
hardware_interface::return_type write(const rclcpp::Time &time, const rclcpp::Duration &period) override
Writes commands to the hardware from the command interfaces.
Definition arm_hardware.cpp:403
bioscara_hardware_drivers::err_type_t start_homing(const std::string name, float velocity)
wrapper method to start homing.
Definition arm_hardware.cpp:681
hardware_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State &previous_state) override
Called on the transistion from the inactive to the active state.
Definition arm_hardware.cpp:275
std::unordered_map< std::string, std::unique_ptr< bioscara_hardware_drivers::BaseJoint > > _joints
unordered map storing the pointers to BaseJoint objects. This will either be a MockJoint or Joint.
Definition arm_hardware.hpp:443
bioscara_hardware_drivers::err_type_t activate_joint(const std::string name)
Enables each joint, enables the stall detection and sets the maximmum acceleration.
Definition arm_hardware.cpp:722
hardware_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &previous_state) override
Called on the transistion from the active to the inactive state.
Definition arm_hardware.cpp:328
hardware_interface::CallbackReturn on_error(const rclcpp_lifecycle::State &previous_state) override
Called when an error in any state or state transition is thrown.
Definition arm_hardware.cpp:646
hardware_interface::return_type read(const rclcpp::Time &time, const rclcpp::Duration &period) override
Reads from the hardware and populates the state interfaces.
Definition arm_hardware.cpp:348
hardware_interface::CallbackReturn on_init(const hardware_interface::HardwareComponentInterfaceParams &params) override
Called on initialization to the unconfigured state.
Definition arm_hardware.cpp:28
bioscara_hardware_drivers::err_type_t deactivate_joint(const std::string name)
Disables each joint.
Definition arm_hardware.cpp:776
std::mutex mtx
A mutex that is used to prevent concurrent access to hardware and _joint_command_modes.
Definition arm_hardware.hpp:508
hardware_interface::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &previous_state) override
Called on the transistion from the inactive, unconfigured and active to the finalized state.
Definition arm_hardware.cpp:183
std::unordered_map< std::string, std::set< std::string > > _joint_command_modes
unordered map of sets storing the active command interfaces for each joint.
Definition arm_hardware.hpp:467
File including the Joint class.
File including the MockJoint class.
err_type_t
Enum defining common error types.
Definition uErr.h:23
Definition arm_hardware.hpp:38
constexpr char HW_IF_HOME[]
Definition arm_hardware.hpp:39
configuration structure holding the passed paramters from the ros2_control urdf
Definition arm_hardware.hpp:338
float reduction
[float] Gear reduction of the joint
Definition arm_hardware.hpp:360
joint_homing_config_t homing
Holding the joint_homing_config_t configruation values.
Definition arm_hardware.hpp:430
u_int8_t hold_current
[int, DEC] Hold current of stepper driver in 0-100 % of 2.5A output (check uStepper doc....
Definition arm_hardware.hpp:396
float max
[float] Upper joint limit in joint units
Definition arm_hardware.hpp:382
float min
[float] Lower joint limit in joint units
Definition arm_hardware.hpp:371
u_int8_t stall_threshold
[int, DEC] Stall protection threshold in 0-255, where lower is more sensitive.
Definition arm_hardware.hpp:404
float max_acceleration
[float] Maximum permitted joint acceleration (and deceleration).
Definition arm_hardware.hpp:424
u_int8_t drive_current
[int, DEC] Drive current of stepper driver in 0-100 % of 2.5A output (check uStepper doc....
Definition arm_hardware.hpp:389
int i2c_address
[int, HEX] I2C device adress
Definition arm_hardware.hpp:344
float max_velocity
[float] Maximum permitted joint velocity.
Definition arm_hardware.hpp:414
configuration structure holding the passed homing paramters from the ros2_control urdf
Definition arm_hardware.hpp:297
float speed
[float] Signed homing velocity.
Definition arm_hardware.hpp:304
u_int8_t current
[int, DEC] Homing current between 0 and 100.
Definition arm_hardware.hpp:319
float acceleration
[float] Joint acceleration during homing.
Definition arm_hardware.hpp:328
u_int8_t threshold
[int, DEC] Encoder error threshold 0 to 255.
Definition arm_hardware.hpp:311