ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Arduino code for custom robot arm

asked 2018-01-10 20:46:07 -0500

Evgenia gravatar image

updated 2018-01-10 21:28:20 -0500

Can you give me an example of arduino code for moveit. I can’t find any examples. Which information should node publish to controller? Servomotor pose or so?. Maybe there are some tutorials?

edit retag flag offensive close merge delete

Comments

You want someone to write code for you? If that's what you're looking for that's not how it works. We'll hekp you with problems but we won't do your work for you. If I'm mistaken, please let me know and update your question with more detail.

jayess gravatar image jayess  ( 2018-01-10 21:06:51 -0500 )edit

Thank you for your comment! I’ve updated my question.

Evgenia gravatar image Evgenia  ( 2018-01-10 21:29:34 -0500 )edit

2 Answers

Sort by » oldest newest most voted
3

answered 2018-01-16 04:33:05 -0500

updated 2018-03-05 04:43:28 -0500

#if defined(ARDUINO) && ARDUINO >= 100 #include "Arduino.h" #else #include <wprogram.h> #endif

 #include <Servo.h> 
 #include <ros.h>
 #include <std_msgs/UInt16.h>

 ros::NodeHandle  nh;

 Servo servo1;
 Servo servo2;
 Servo servo3;
 Servo servo4;
 Servo servo5;
 Servo servo6;


  void servo_cb1( const std_msgs::UInt16& cmd_msg){
  servo1.write(cmd_msg.data); //set servo angle, should be from 0-180  

  }

  void servo_cb2( const std_msgs::UInt16& cmd_msg){
   servo2.write(cmd_msg.data); //set servo angle, should be from 0-180  

   }

   void servo_cb3( const std_msgs::UInt16& cmd_msg){
   servo3.write(cmd_msg.data); //set servo angle, should be from 0-180  

   }

   void servo_cb4( const std_msgs::UInt16& cmd_msg){
   servo4.write(cmd_msg.data); //set servo angle, should be from 0-180  

   }
  void servo_cb5( const std_msgs::UInt16& cmd_msg){
  servo5.write(cmd_msg.data); //set servo angle, should be from 0-180  

  }

  void servo_cb6( const std_msgs::UInt16& cmd_msg){
  servo6.write(cmd_msg.data); //set servo angle, should be from 0-180  

  }


   ros::Subscriber<std_msgs::UInt16> sub1("servo1", servo_cb1);
   ros::Subscriber<std_msgs::UInt16> sub2("servo2", servo_cb2);
   ros::Subscriber<std_msgs::UInt16> sub3("servo3", servo_cb3);
   ros::Subscriber<std_msgs::UInt16> sub4("servo4", servo_cb4);
   ros::Subscriber<std_msgs::UInt16> sub5("servo5", servo_cb5);
   ros::Subscriber<std_msgs::UInt16> sub6("servo6", servo_cb6);

   void setup(){
    pinMode(13, OUTPUT);
    pinMode(12, OUTPUT);
    pinMode(11, OUTPUT);
    pinMode(10, OUTPUT);
    pinMode(9, OUTPUT);
    pinMode(8, OUTPUT);

    nh.initNode();
    nh.subscribe(sub1);
    nh.subscribe(sub2);
    nh.subscribe(sub3);
    nh.subscribe(sub4);
    nh.subscribe(sub5);
    nh.subscribe(sub6);

    servo1.attach(13); //attach it to pin 13
    servo2.attach(12);
    servo3.attach(11); //attach it to pin 11
    servo4.attach(10);
    servo1.attach(9); //attach it to pin 9
    servo2.attach(8);

    }

    void loop(){
    nh.spinOnce();
    delay(1);
     }
edit flag offensive delete link more

Comments

Thank you! It is very useful!

Evgenia gravatar image Evgenia  ( 2018-01-16 17:28:45 -0500 )edit

Move it , i am also trying to figure out , once i figure it our i will share .

For move it , you need to first sort out the URDF model of the robotic arm .

I have a 16 channel PCA9685 servo module (it can be operated via I2C). I am trying to figure out how to control the module vai nodemcu.

chrissunny94 gravatar image chrissunny94  ( 2018-01-16 23:10:11 -0500 )edit
1
chrissunny94 gravatar image chrissunny94  ( 2018-01-16 23:38:48 -0500 )edit

Thank you! I'll try!

Evgenia gravatar image Evgenia  ( 2018-01-17 17:24:17 -0500 )edit
2

answered 2018-01-15 18:17:43 -0500

Evgenia gravatar image

Finaly, I've got how do this. There is topic: /joint_states it gives radians of position of each knee of manipulator. I've transformed this data to servo steps in ros node and then sent them to arduino using UInt8MultiArray! And it works! After all arduino subscriber looks like this:

void servo_cb( const std_msgs::UInt8MultiArray& cmd_msg){
    for(short i = 0; i<=4; i++)
        myservo[i].write(cmd_msg.data[i]);
}
edit flag offensive delete link more

Comments

Hello @Evgenia, is there anyway you can show how you have put these values into an array? I am struggling to reproduce what you have described here...

matthewmarkey gravatar image matthewmarkey  ( 2020-05-31 09:48:21 -0500 )edit

have you sought the issue, i am also struggling for the same problem. Can you help me @matthewmarkey

Rakee003 gravatar image Rakee003  ( 2021-10-12 23:49:59 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-01-10 20:46:07 -0500

Seen: 1,140 times

Last updated: Mar 05 '18