You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
I am using this library together with my NodeMCU and other ESP8266-12 modules.
But the library/compiler throws the following error: "fatal error: avr/pgmspace.h: No such file or directory".
I am still getting error, this is the Arduino output console:
Arduino:
1.8.5 (Mac OS X), TD: 1.42, Board: "Generic ESP8266 Module, 80 MHz, ck, 26 MHz, 40MHz, QIO, 512K (no SPIFFS), 2, v2 Lower Memory, Disabled, None, Only Sketch, 115200"
WARNING: library Rosserial_Arduino_Library claims to run on (avr) architecture(s) and may be incompatible with your current board which runs on (esp8266) architecture(s).
In file included from /Users/rodri/Documents/Arduino/libraries/Rosserial_Arduino_Library/src/ros/node_handle.h:43:0,
from /Users/rodri/Documents/Arduino/libraries/Rosserial_Arduino_Library/src/ros.h:38,
from /var/folders/kz/pqrn72016518fys3qx9_qh3m0000gp/T/arduino_modified_sketch_74395/pubsub.pde:6:
/Users/rodri/Documents/Arduino/libraries/Rosserial_Arduino_Library/src/rosserial_msgs/RequestParam.h:12:19: error: rosserial_msgs::REQUESTPARAM causes a section type conflict with __c
static const char REQUESTPARAM[] PROGMEM = "rosserial_msgs/RequestParam";
^
In file included from /Users/rodri/Library/Arduino15/packages/esp8266/hardware/esp8266/2.4.1/cores/esp8266/Arduino.h:255:0,
from sketch/pubsub.pde.cpp:1:
/Users/rodri/Library/Arduino15/packages/esp8266/hardware/esp8266/2.4.1/cores/esp8266/pgmspace.h:16:51: note: '__c' was declared here
#define PSTR(s) (extension({static const char __c[] PROGMEM = (s); &__c[0];}))
^
/Users/rodri/Documents/Arduino/libraries/Rosserial_Arduino_Library/src/std_msgs/Empty.h:34:35: note: in expansion of macro 'PSTR'
const char * getMD5(){ return PSTR( "d41d8cd98f00b204e9800998ecf8427e" ); };
^
exit status 1
Error compiling for board Generic ESP8266 Module.
The text was updated successfully, but these errors were encountered:
Hello,
I do not think this issue is related with rosserial because I cannot see
mention of `avr/pgmspace.h` in the current [ros.h](
https://github.com/ros-drivers/rosserial/blob/fe1e233f39d56931b5e223c5e53a2d9c2f9fb664/rosserial_arduino/src/ros_lib/ros.h)
file.
Furthermore we already used ESP8266 board with rosserial without facing
this issue.
Please, make sure you have a recent version of `rosserial_arduino` (maybe
you need to use the git version instead of the one provided by your
distribution if it is too old.
Le mer. 13 juin 2018 à 12:39, R0dri <[email protected]> a écrit :
I am using this library together with my NodeMCU and other ESP8266-12
modules.
But the library/compiler throws the following error: "fatal error:
avr/pgmspace.h: No such file or directory".
I found the following solution:
at ros.h you have to replace
#include <avr\pgmspace.h>
with
#if (defined(*AVR*))
#include <avr\pgmspace.h>
#else
#include <pgmspace.h>
#endif
This works fine for me.
This solution was suggested by:
SodaqMoja/Sodaq_DS3231#5 <http://url> having a
similar issue with another library. Should this be a merge request?
—
You are receiving this because you are subscribed to this thread.
Reply to this email directly, view it on GitHub
<#377>, or mute the thread
<https://github.com/notifications/unsubscribe-auth/AIb5YEXpbbhJtRMk2KyZdkUl5TQcD2rBks5t8JeTgaJpZM4Ulhif>
.
I'm sorry, you where right. I tried to use the libraries imported by the Arduino IDE library manager. Just downloaded and compiled from source and it worked flawlessly.
I am using this library together with my NodeMCU and other ESP8266-12 modules.
But the library/compiler throws the following error: "fatal error: avr/pgmspace.h: No such file or directory".
I found the following solution:
at ros.h I replaced
#include <avr\pgmspace.h>
with
This solution was suggested by: https://github.com/SodaqMoja/Sodaq_DS3231/issues/5 having a similar issue with another library.
I am still getting error, this is the Arduino output console:
The text was updated successfully, but these errors were encountered: