Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

How to control motor pwm or moving of RPLIDAR A1 in matlab #7

Open
wnghdwnsrl opened this issue Jan 12, 2021 · 6 comments
Open

How to control motor pwm or moving of RPLIDAR A1 in matlab #7

wnghdwnsrl opened this issue Jan 12, 2021 · 6 comments

Comments

@wnghdwnsrl
Copy link

Hello, I 'm using RPLIDAR A1 for project in matlab 2019b
but there are two problem using it.

  1. I can't control RPLDIAR A1 pwm by using SetMotorPWMRequestRPLIDAR() or SetLidarSpinSpeedRequestRPLIDAR().
    How can i control RPLIDAR A1 pwm another way?( I couldn't understand well ismet55555's issue)
  2. There was a problem using RPLDIAR with Dynamixel MX-64 motor to make 3d scan. When i make RPLIDAR scan while MX-64 tilt repeatedly, it looks odd.
    The code is when MX-64 move, next get points of PRLIDAR by using GetScanDataResponsePRLIDAR(), From the beginning it just get next data after first 360 number of data, not the data after MX-64 move.
    I just thought it could solve by making this operate like RPLIDAR scan just once 360points and MX-64 move repeatedly.
    Is there any way to control RPLIDAR stop and turn agian in matlab?
@lebarsfa
Copy link
Member

lebarsfa commented Jan 12, 2021

Hello,

  1. I am not sure if there is a software way to control the speed of the A1, in my comment S3 RPLIDAR Does Not Respond to Changes in Motor PWM  #5 (comment) I was not mentioning the A1 because of the comments in https://github.com/Slamtec/rplidar_sdk/blob/504a2e5dfb544124c3edbb94419f866ed274b99c/sdk/sdk/include/rplidar_driver.h#L180, you might need to ask SLAMTEC if there is an undocumented way to do that...
  2. Maybe try StopMotorRPLIDAR() and StartMotorRPLIDAR() that I just added in https://github.com/ENSTABretagneRobotics/Hardware-MATLAB/releases/download/v1.5.3/hardwarex_with_3rd_support.zip (not tested), but I am not sure this would be a viable workaround...

@wnghdwnsrl
Copy link
Author

Thank you for your comment!

StartMotorRPLIDAR() and StopMotorRPLIDAR() function in hardwarex_with_3rd_support file are working.

Thank you for your help again

@wnghdwnsrl
Copy link
Author

Hello, I used StartMotorRPLIDAR() and StopMotorRPLIDAR() functions well
But there is another problem using two functions.
When I stopped motor and started RPLIDAR A1 again, GetScanDataResponse() didn't work and matlab had forcely ended. (exit all pages).
Is there any solutions about this problem?

@lebarsfa
Copy link
Member

Maybe before the StopMotorRPLIDAR(), we need StopRequestRPLIDAR(), and after StartMotorRPLIDAR(), we need StartScanRequestRPLIDAR() before calling GetScanDataResponse().
If it does not work, in test_rplidar.m, check

% If bStartScanModeAtStartup to 0 in RPLIDAR0.txt...
%[result] = ResetRequestRPLIDAR(pRPLIDAR)
%pause(2)
%[result] = GetStartupMessageRPLIDAR(pRPLIDAR)
%[result] = StopRequestRPLIDAR(pRPLIDAR)
%[result, ModelID, HardwareVersion, FirmwareMajor, FirmwareMinor, SerialNumber] = GetInfoRequestRPLIDAR(pRPLIDAR)
%[result, typicalscanmodeid] = GetTypicalScanModeRPLIDAR(pRPLIDAR)
%[result, scanmodeids, scanmodeuspersamples, scanmodemaxdistances, scanmodeanstypes, scanmodenames] = GetAllSupportedScanModesRPLIDAR(pRPLIDAR)
%[result] = SetMotorPWMRequestRPLIDAR(pRPLIDAR, 660)
%[result] = StartScanRequestRPLIDAR(pRPLIDAR)
where it is suggested that if you set bStartScanModeAtStartup to 0 in RPLIDAR0.txt you need to uncomment those lines. Maybe you will need to follow a similar logic after the StartMotorRPLIDAR()...

@wnghdwnsrl
Copy link
Author

Thank you, it works well with no errors. but i have one more question.
when I stop and restart motor and move RPLIDAR A1 scan area, then it scans just before data( not new area). I think i need to clear buffer to scan new data.
If I want to clear RPLIDAR A1 buffer, Is there any solution that you can advise?

@lebarsfa
Copy link
Member

I just added ClearCacheRPLIDAR() (which calls clearNetSerialRxCache() from the SLAMTEC C++ SDK), see v1.5.5 release : https://github.com/ENSTABretagneRobotics/Hardware-MATLAB/releases/tag/v1.5.5. Otherwise, I do not see an obvious way to solve this problem...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants