ros2_canopen  master
C++ ROS CANopen Library
Classes | Namespaces | Typedefs
motor.hpp File Reference
#include <algorithm>
#include <atomic>
#include <bitset>
#include <condition_variable>
#include <functional>
#include <iostream>
#include <limits>
#include <mutex>
#include <thread>
#include "rclcpp/rclcpp.hpp"
#include "canopen_402_driver/default_homing_mode.hpp"
#include "canopen_402_driver/mode_forward_helper.hpp"
#include "canopen_402_driver/profiled_position_mode.hpp"
#include "canopen_base_driver/diagnostic_collector.hpp"
#include "canopen_base_driver/lely_driver_bridge.hpp"
Include dependency graph for motor.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  ros2_canopen::Motor402
 

Namespaces

 ros2_canopen
 

Typedefs

typedef ModeForwardHelper< MotorBase::Profiled_Velocity, int32_t, 0x60FF, 0, 0 > ros2_canopen::ProfiledVelocityMode
 
typedef ModeForwardHelper< MotorBase::Profiled_Torque, int16_t, 0x6071, 0, 0 > ros2_canopen::ProfiledTorqueMode
 
typedef ModeForwardHelper< MotorBase::Cyclic_Synchronous_Position, int32_t, 0x607A, 0, 0 > ros2_canopen::CyclicSynchronousPositionMode
 
typedef ModeForwardHelper< MotorBase::Cyclic_Synchronous_Velocity, int32_t, 0x60FF, 0, 0 > ros2_canopen::CyclicSynchronousVelocityMode
 
typedef ModeForwardHelper< MotorBase::Cyclic_Synchronous_Torque, int16_t, 0x6071, 0, 0 > ros2_canopen::CyclicSynchronousTorqueMode
 
typedef ModeForwardHelper< MotorBase::Velocity, int16_t, 0x6042, 0,(1<< Command402::CW_Operation_mode_specific0)|(1<< Command402::CW_Operation_mode_specific1)|(1<< Command402::CW_Operation_mode_specific2)> ros2_canopen::VelocityMode
 
typedef ModeForwardHelper< MotorBase::Interpolated_Position, int32_t, 0x60C1, 0x01,(1<< Command402::CW_Operation_mode_specific0)> ros2_canopen::InterpolatedPositionMode