ENSTABretagneRobotics / Hardware-MATLAB

8 stars 2 forks source link

S1 RPLIDAR Hardware Information Does not Show up #4

Closed ismet55555 closed 4 years ago

ismet55555 commented 4 years ago

When compiling the interface library without the RPLIDAR SDK support (ENABLE_RPLIDAR_SDK_SUPPORT commented out) on a S1 RPLIDAR. LIDAR hardware information returns zeros.

However the RPLIDAR still works and acquires in DenseBoost mode and no errors are shown during connection, usage, and disconnection.

The hardware information, however does show when using the following in RPLIDAR0.txt:

% bStartScanModeAtStartup
1

Here is the output to pRPLIDAR.value:

ans = 

  struct with fields:

                        drv: []
                  RS232Port: [1×1 struct]
                      model: 0
                   hardware: 0
             firmware_major: 0
             firmware_minor: 0
               SerialNumber: [0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0]
                  Tstandard: 0
                   Texpress: 0
                esdata_prev: [1×84 uint8]
                 pfSaveFile: [1×1 struct]
              szCfgFilePath: [1×256 int8]
                  szDevPath: [1×256 int8]
                   BaudRate: 256000
                    timeout: 2500
               threadperiod: 50
               bSaveRawData: 1
    bStartScanModeAtStartup: 0
                   ScanMode: 1
                 motordelay: 10
                    maxhist: 180
              alpha_max_err: 0.0100
                  d_max_err: 0.1000

The script that was used:

% Clear it all
clc
clear all
close all

% Load the hardwarex rplidar interface library
hardwarex_init;

% Create the rplidar object
pRPLIDAR = CreateRPLIDAR();

% Connect the lidar
[result_connect] = ConnectRPLIDAR(pRPLIDAR, 'RPLIDAR0.txt')

% Select the scan mode (0: Scan, 1: DenseBoost)
pRPLIDAR.value.ScanMode = 1;

pRPLIDAR.value

% =========================

% Get Startup Messages in standard out
[result_get_startup] = GetStartupMessageRPLIDAR(pRPLIDAR)

% Stop the lidar if it is running
[result_stop] = StopRequestRPLIDAR(pRPLIDAR)

% Set the motor power
[result_set_motorPWM] = SetMotorPWMRequestRPLIDAR(pRPLIDAR, 1023)

% Get all the available scan mode values (Must enable ENABLE_RPLIDAR_SDK_SUPPORT)
[result_typical_scanmode, scanmodeid] = GetTypicalScanModeRPLIDAR(pRPLIDAR)

% Get the scanmode options for this lidar (Must enable ENABLE_RPLIDAR_SDK_SUPPORT)
[result_all_supported_scanmodes, scanmodeids, scanmodeuspersamples, scanmodemaxdistances, scanmodeanstypes, scanmodenames] = GetAllSupportedScanModesRPLIDAR(pRPLIDAR)

% Start the scan
[result_start_scan] = StartOtherScanRequestRPLIDAR(pRPLIDAR, pRPLIDAR.value.ScanMode)
pause(2)

% Get a data sample
[result_get_data, distances, angles, bNewScan] = GetOtherScanDataResponseRPLIDAR(pRPLIDAR)
str = sprintf('Distance at %f deg = %f m\n', angles(1)*180.0/pi, distances(1));
disp(str);

[result, byteCount] = GetFIFORPLIDAR(pRPLIDAR)

% Create the plot
fig = figure('Position',[200 200 400 400],'NumberTitle','off');

% Force the figure to have input focus (required to capture keys).
set(fig,'WindowStyle','Modal'); 
axis('off');
scale = 6;
axis([-scale,scale,-scale,scale])

% Start the DAQ
count = 0; 
alldistances = []; 
allangles = [];
key = 0;
fps_log = [];

while (isempty(key)||(key ~= 27)) % Wait for ESC key (ASCII code 27).
    tic

    % Get the FIFO buffer size (Must disable ENABLE_RPLIDAR_SDK_SUPPORT)
    [result, byteCount] = GetFIFORPLIDAR(pRPLIDAR);

    % Get the lidar data
    [result, distances, angles, bNewScan] = GetOtherScanDataResponseRPLIDAR(pRPLIDAR);

    % Add on to array;
    alldistances = [alldistances distances]; 
    allangles = [allangles angles]; 

    %if bNewScan
%     if count > 360
    if count > 720/32
       plot(alldistances.*cos(allangles), alldistances.*sin(allangles), '.');
       key = get(gcf,'CurrentCharacter');

       count = 0; 
       alldistances = []; 
       allangles = []; 

       axis([-scale,scale,-scale,scale]);
       grid on

       drawnow

       fps_log = [fps_log, 1 / toc];
    end    
    count = count + 1;
end

% Close the figure
close(fig);

% Show the iterations per second average
fprintf("\n\nMean Iterations per Second: %.2f +/- %.3f Hz\n", mean(fps_log), std(fps_log))

% Disconnect
[result_disconnect] = DisconnectRPLIDAR(pRPLIDAR)

% Remove the library pointer reference
DestroyRPLIDAR(pRPLIDAR);

% Clear the MATLAB reference
clear pRPLIDAR;

% Unload the interface library
unloadlibrary('hardwarex');

The RPLIDAR0.txt file contents:

% Server TCP port (e.g. :4001), client IP address and TCP port (e.g. 127.0.0.1:4001) or local RS232 port
%127.0.0.1:55555
COM3
% BaudRate
256000
% Timeout (in ms)
2500
% threadperiod (in ms, require associated thread)
50
% bSaveRawData (require associated thread)
1
% bStartScanModeAtStartup
0
% ScanMode (0 : SCAN, 1 : EXPRESS_SCAN, 2 : FORCE_SCAN, or if using GetOtherScanDataResponseRPLIDAR(), the available values and modes might be different, see https://github.com/ENSTABretagneRobotics/Hardware-MATLAB/issues/3#issuecomment-661349278)
1
% motordelay (in ms)
10
% maxhist (0 : try to automatically remove old data, around 180 : advised for SCAN mode, around 360 : advised for EXPRESS_SCAN mode, require associated thread)
180
% alpha_max_err (in rad)
0.01
% d_max_err (in m)
0.1
ismet55555 commented 4 years ago

Never mind. Although this does happen, the most simple solution is to just use the following endpoint method: [result, modelID, hardwareVersion, firmwareMajor, firmwareMinor, serialNumber] = GetInfoRequestRPLIDAR(pRPLIDAR)

lebarsfa commented 4 years ago

Here are some clarifications :

ismet55555 commented 4 years ago

Thanks for the clarification!

Yeah in the test script I posted, GetAllSupportedScanModesRPLIDAR() and GetTypicalScanModeRPLIDAR() do come back with an error code 17. I probably should have mentioned that. Just using that script to test some things.