DRCL
  • Welcome to DRC Lab.
  • Professor
  • Member
    • Researcher
    • Alumni
  • Research
    • On Going Projects
      • 복합임무형 다족형 로봇 플랫폼 기술개발
      • 미래도전국방기술 과제
    • Previous Projects
      • HuboQ Remastered
      • Novel Concept Gear Reducer
      • High-Speed Autonomous Delivery Robot
      • TennisBot V1
      • MJ-VESC (Universal Motor Controller)
        • MJ-VESCular
        • MJ-VESCuino
  • Publication (2019~)
  • Lecture
    • Dynamics
    • Modern Robotics
    • Intelligent Robot
    • Smart Machine Microprocessor
  • Memories
    • 2023
    • 2022
    • 2021
    • 2020
    • 2019
  • DRCL Youtube Channel
  • DRCL Hackday.io Page
  • DRCL Github
  • OpenRobot Inc.
  • VESC Shop (for Korean)
Powered by GitBook
On this page
  • 1. What is MJ-VESC?
  • 2. MJ-VESC Firmware Github Page
  • 2.1. Firmware for MJ-VESC VER0.1
  • 2.2. Original Firmware of VESC
  • 2.3. VESC-TOOL 0.95
  • 3. ROS Control Framework for MJ-VESC
  • Attachment
  1. Research
  2. Previous Projects
  3. MJ-VESC (Universal Motor Controller)

MJ-VESCuino

MJ-VESC stackable on Arduino

PreviousMJ-VESCularNextPublication (2019~)

Last updated 4 years ago

If you have any question on MJ-VESC, please leave a topic on 'Board' or send a email to dongilc@mju.ac.kr.

1. What is MJ-VESC?

The MJ-VESC Project was launched to apply the VESC, which is commonly used in electric-skating board, to "the Robotics area".

The unique thing of MJ-VESC is stack-able design. The board form factor is Arduino Shield Type. So, it can be stacked on the Arduino.

The hardware improvements from the existing VESC are as follows:

  1. In FOC control, we provide high torque control even at low speed.

  2. Position control is possible at Hall sensor commutation with AB encoder (without index).

  3. Hall & Encoder Hybrid Commutation for more precise position control.

  4. More accurate current control by changing shunt resistor from 0.5mohm to 2mohm.

  5. Improved CAN Communication Noise Filter using split terminal resistor and EMI filter.

The software improvements from the existing VESC are as follows:

  1. High accuracy position control using "DPS speed control" (Degree Per Second).

  2. VESC - Arduino high speed communication using SPI communication.

  3. Debugging terminal using extra serial communication.

2. MJ-VESC Firmware Github Page

2.1. Firmware for MJ-VESC VER0.1

The MJ-VESC Firmware version is based on vesc bldc firmware 3.40 and compatible VESC-TOOL version is 0.95 at this moment.

2.2. Original Firmware of VESC

2.3. VESC-TOOL 0.95

3. ROS Control Framework for MJ-VESC

In this page, I will explain how to setup MJ-VESC when the high-level controller is based on ROS and communication method is USB.

1. First, run VESC-TOOL (I assume that the motor setup of all the MJ-VESC is already finished)

./vesc_tool_0.95

Connect MJ-VESC ID=0.

Go to App Settings -> General -> APP to USE : Custom User App 
Go to App Settings -> General -> Send CAN Status : False.

2. Connect MJ-VESC ID=1~ using CAN-FORWARD (Setup all the other MJ-VESCs as below in case of ID>=1)

Go to App Settings -> General -> APP to USE : UART
Go to App Settings -> General -> Send CAN Status : True

The VESC-TOOL setup is finished.

3. Download attached source code named 'vesc_control_ex1.zip'. You also need vesc library for ROS. Download 'vesc.zip' which is ros driver for MJ-VESC.

4. Unzip and put those folders at your catkin workspace and then build. When you build, you may need dependencies as follows:

serial
ackermann-msgs

You can install above packages like this (when you use 'ros-melodic' then replace 'kinetic' to 'melodic').

sudo apt-get install ros-kinetic-ackermann-msgs ros-kinetic-serial

5. Run the ROS example using launch file below. Change argument 'port' depend on your condition.

roslaunch vesc_control_ex1 vesc_control_ex1_teleop.launch port:=/dev/ttyACM1

The main function of 'vesc_control_ex1_node.cpp' is as below.

/*
 * Main Function
 * 
 */
int main(int argc, char **argv)            
{
  ros::init(argc, argv, "vesc_control_node");

  // loop freq
  int rate_hz = 50;	//hz

  // TeleopVesc Class
  const int num_of_vesc = VESC_ID_END+1;//4;
  TeleopVesc *teleop_vesc = new TeleopVesc(num_of_vesc);
  teleop_vesc->enable.data = false;

  // ROS Loop
  int cnt_lp = 0;
  ros::Rate loop_rate(rate_hz); //Hz
  ROS_INFO("Start Tele-operation");
  while (ros::ok())
  {
		teleop_vesc->enable.data = true;

		// read encoder data.
		//teleop_vesc->requestCustoms();
		//ROS_INFO("rps_0:%.2f(dps_0:%.2f), rad_0:%.2f", teleop_vesc->rps[0], teleop_vesc->rps[0]*RPS2DPS, teleop_vesc->rad[0]);
		//ROS_INFO("rps_1:%.2f(dps_1:%.2f), rad_1:%.2f", teleop_vesc->rps[1], teleop_vesc->rps[1]*RPS2DPS, teleop_vesc->rad[1]);
		//ROS_INFO("rps_2:%.2f(dps_2:%.2f), rad_2:%.2f", teleop_vesc->rps[2], teleop_vesc->rps[2]*RPS2DPS, teleop_vesc->rad[2]);
		//ROS_INFO("rps_3:%.2f(dps_3:%.2f), rad_3:%.2f", teleop_vesc->rps[3], teleop_vesc->rps[3]*RPS2DPS, teleop_vesc->rad[3]);

		// // current example (A)
		//teleop_vesc->current[0] = 4.0;
		//teleop_vesc->current[1] = 4.0;
		//teleop_vesc->current[2] = -1.0;
		//teleop_vesc->current[3] = 1.0;
		//teleop_vesc->setCurrentOut();

		// // brake example (A)
		//teleop_vesc->brake[0] = 10.0;
		//teleop_vesc->brake[1] = 10.0;
		//teleop_vesc->brake[2] = 5.0;
		//teleop_vesc->brake[3] = 8.0;
		//teleop_vesc->setBrakeOut();

		// // speed example (erpm = rev/min*polepair, polepair=Encoder Ratio@vesc_tool)
		//teleop_vesc->speed[0] = 0.//-(15000.0 - 5000.0);
		//teleop_vesc->speed[1] = 1000.//(15000.0 + 5000.0);
		//teleop_vesc->speed[2] = -1000.0;
		//teleop_vesc->speed[3] = 5000.0;
		//teleop_vesc->setSpeedOut();

		// // duty example (0.005~0.95)
		//teleop_vesc->duty[0] = 0.1;
		//teleop_vesc->duty[1] = 0.1;
		//teleop_vesc->duty[2] = 0.1;
		//teleop_vesc->duty[3] = 0.5;
		//teleop_vesc->setDutyCycleOut();

		// // position example (0~360 deg)
		//teleop_vesc->position[0] = 0.;
		//teleop_vesc->position[1] = 15.;
		//teleop_vesc->position[2] = 270.;
		//teleop_vesc->position[3] = -45.;
		//teleop_vesc->setPositionOut();

		// Custom example
		teleop_vesc->custom_cmd_type[0] = COMM_SET_DUTY;
		teleop_vesc->custom_cmd_value[0] = 0.6;
		teleop_vesc->custom_cmd_type[1] = COMM_SET_DPS;
		teleop_vesc->custom_cmd_value[1] = 1000.;
		//teleop_vesc->custom_cmd_type[2] = COMM_SET_DPS;
		//teleop_vesc->custom_cmd_value[2] = -1000.;
		//teleop_vesc->custom_cmd_type[3] = COMM_SET_DPS;
		//teleop_vesc->custom_cmd_value[3] = 1000.;
		//teleop_vesc->custom_cmd_type[1] = COMM_SET_DPS;
		//teleop_vesc->custom_cmd_value[1] = 0.;
		teleop_vesc->setCustomOut();

		ros::spinOnce();
		loop_rate.sleep();
  }

  return 0;
}

You can test 'SetCurrent', 'SetDutyCycle', 'SetSpeed', 'SetPosition', 'SetBrake', 'SetDPS' by un-commenting each functions. "COMM_SET_DPS" is only valid when you use 'teleop_vesc->custom_cmd_type'.

All the encoder data are stored at 'teleop_vesc->rps[id]' and 'teleop_vesc->rad[id]'. The 'rps' is rad/sec' and The 'rad' is Radian. You can easily use these variables at main function.

Attachment

GitHub - dongilc/bldc-mjvesc_v01_3.40: mjvesc firmware stableGitHub
GitHub - vedderb/bldc: The code for my custom BLDC controller.GitHub
GitHub - vedderb/vesc_tool: The source code for VESC Tool. See vesc-project.comGitHub
Logo
Logo
Logo
49KB
vesc.zip
archive
VESC ROS Driver
6KB
vesc_control_ex1.zip
archive
MJ-VESC ver0.1
Stacked three MJ-VESCs with 3D printed Case.
Stacked four MJ-VESCs on Arduino Due with 3D printed Case.