Skip to content

KobeKosenRobotics/dynamixel_wrapper

Repository files navigation

Melodic build Noetic build

dynamixel_wrapper

Dynamixel SDK wrapper library for ROS

1. Setup

cd ~/catkin_ws/src
git clone https://github.com/KobeKosenRobotics/dynamixel_wrapper
cd ..
# うまく行かない時はapt update
rosdep install -i -y --from-paths src
catkin build

2. include pathの設定

自作のROS Packageから利用するための設定

  • CMakeList.txtのfind_packageにdynamixel_wrapperを追記
find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  tf
  dynamixel_wrapper #これを追記
)
  • package.xmlに以下の3行を追記
<build_depend>dynamixel_wrapper</build_depend>
<build_export_depend>dynamixel_wrapper</build_export_depend>
<exec_depend>dynamixel_wrapper</exec_depend>

3. sample code

-90[deg]~90[deg]の間を往復するサンプル

#include <ros/ros.h>

#include <iostream>
#include <string>

#include <dynamixel_wrapper/dynamixel_wrapper.h>


int main(int argc, char **argv){
    
    ros::init(argc, argv, "position_node");
    ros::NodeHandle n;

    double rate=10.0;
    ros::Rate loop_rate(rate);
    
    //dynamixel hub setting
    std::string port_name("/dev/ttyUSB0");
    int baudrate=1000000;
    dynamixel_wrapper::dynamixel_wrapper_base dxl_base(port_name,baudrate);

    //dynamixel motor setting
    int motor_id=0;
    int operating_mode=5;
    dynamixel_wrapper::dynamixel_wrapper motor0(motor_id,dxl_base,dynamixel_wrapper::XM430_W350_R,operating_mode);

    //setting
    motor0.setTorqueEnable(false);
    motor0.setCurrentLimit(40.0);
    motor0.setTorqueEnable(true);

    double goal_angle=90.0;

    while (n.ok())  {
        motor0.setGoalPosition(goal_angle);

        if(std::abs(motor0.getPresentPosition()-goal_angle)<1.0){
            goal_angle*=-1;
        }
        ROS_INFO("Motor angle %lf[deg]",motor0.getPresentPosition());
        ros::spinOnce();
        loop_rate.sleep();
        
    }
    
    return 0;
}

About

Dynamixel SDK wrapper library for ROS

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published