예제 #1
0
// Output the contents of a file, first parameter is the filename, second is the limit ( in number of lines to output )
void SimpleShell::cat_command( string parameters, StreamOutput* stream ){
    
    // Get parameters ( filename and line limit ) 
    string filename          = this->absolute_from_relative(shift_parameter( parameters ));
    string limit_paramater   = shift_parameter( parameters );
    int limit = -1;
    if( limit_paramater != "" ){ limit = int(atof(limit_paramater.c_str())); }
   
    // Open file 
    FILE *lp = fopen(filename.c_str(), "r");
    if(lp == NULL) {
    	stream->printf("File not found: %s\r\n", filename.c_str());
    	return;
    }
    string buffer;
    int c;
    int newlines = 0; 
    
    // Print each line of the file
    while ((c = fgetc (lp)) != EOF){
    	buffer.append((char *)&c, 1);
        if( char(c) == '\n' ){
        	newlines++;
        	stream->printf("%s", buffer.c_str());
        	buffer.clear();
        }
        if( newlines == limit ){ break; }
    }; 
    fclose(lp);

}
예제 #2
0
// used to test out the get public data events
void SimpleShell::get_command( string parameters, StreamOutput* stream){
    int what= get_checksum(shift_parameter( parameters ));
    void *returned_data;

    if(what == get_temp_command_checksum) {
        string type= shift_parameter( parameters );
        bool ok= this->kernel->public_data->get_value( temperature_control_checksum, get_checksum(type), current_temperature_checksum, &returned_data );

        if(ok) {
            struct pad_temperature temp=  *static_cast<struct pad_temperature*>(returned_data);
            stream->printf("%s temp: %f/%f @%d\r\n", type.c_str(), temp.current_temperature, temp.target_temperature, temp.pwm);
        }else{
            stream->printf("%s is not a known temperature device\r\n", type.c_str());
        }

    }else if(what == get_pos_command_checksum) {
        bool ok= this->kernel->public_data->get_value( robot_checksum, current_position_checksum, &returned_data );

        if(ok) {
            double *pos= static_cast<double *>(returned_data);
            stream->printf("Position X: %f, Y: %f, Z: %f\r\n", pos[0], pos[1], pos[2]);

        }else{
            stream->printf("get pos command failed\r\n");
        }
    }
}
예제 #3
0
// Reload config values from the specified ConfigSource, NOTE used for debugging by dumping the config-cache
void Configurator::config_load_command( string parameters, StreamOutput *stream )
{
    string source = shift_parameter(parameters);
    if(source == "load") {
        THEKERNEL->config->config_cache_load();
        stream->printf( "config cache loaded\r\n");

    } else if(source == "unload") {
        THEKERNEL->config->config_cache_clear();
        stream->printf( "config cache unloaded\r\n" );

    } else if(source == "dump") {
        THEKERNEL->config->config_cache_load();
        THEKERNEL->config->config_cache->dump(stream);
        THEKERNEL->config->config_cache_clear();

    } else if(source == "checksum") {
        string key = shift_parameter(parameters);
        uint16_t cs[3];
        get_checksums(cs, key);
        stream->printf( "checksum of %s = %02X %02X %02X\n", key.c_str(), cs[0], cs[1], cs[2]);

    } else {
        stream->printf( "unsupported option: must be one of load|unload|dump|checksum\n" );
    }
}
예제 #4
0
// Rename a file
void SimpleShell::mv_command( string parameters, StreamOutput *stream )
{
    string from = absolute_from_relative(shift_parameter( parameters ));
    string to = absolute_from_relative(shift_parameter(parameters));
    int s = rename(from.c_str(), to.c_str());
    if (s != 0) stream->printf("Could not rename %s to %s\r\n", from.c_str(), to.c_str());
    else stream->printf("renamed %s to %s\r\n", from.c_str(), to.c_str());
}
예제 #5
0
// used to test out the get public data events
void SimpleShell::set_temp_command( string parameters, StreamOutput* stream){
    string type= shift_parameter( parameters );
    string temp= shift_parameter( parameters );
    double t= temp.empty() ? 0.0 : strtod(temp.c_str(), NULL);
    bool ok= this->kernel->public_data->set_value( temperature_control_checksum, get_checksum(type), &t );

    if(ok) {
        stream->printf("%s temp set to: %3.1f\r\n", type.c_str(), t);
    }else{
        stream->printf("%s is not a known temperature device\r\n", type.c_str());
    }
}
예제 #6
0
static void calc_either_side(Crystal *cr, double incr_val,
                             int *valid, long double *vals[3], int refine,
                             PartialityModel pmodel)
{
	RefList *compare;
	struct image *image = crystal_get_image(cr);

	if ( (refine != REF_DIV) ) {

		Crystal *cr_new;

		/* Crystal properties */
		cr_new = new_shifted_crystal(cr, refine, -incr_val);
		compare = find_intersections(image, cr_new, pmodel);
		scan_partialities(crystal_get_reflections(cr), compare, valid,
		                  vals, 0, pmodel);
		cell_free(crystal_get_cell(cr_new));
		crystal_free(cr_new);
		reflist_free(compare);

		cr_new = new_shifted_crystal(cr, refine, +incr_val);
		compare = find_intersections(image, cr_new, pmodel);
		scan_partialities(crystal_get_reflections(cr), compare, valid,
		                  vals, 2, pmodel);
		cell_free(crystal_get_cell(cr_new));
		crystal_free(cr_new);
		reflist_free(compare);

	} else {

		struct image im_moved;

		/* "Image" properties */
		im_moved = *image;
		shift_parameter(&im_moved, refine, -incr_val);
		compare = find_intersections(&im_moved, cr, pmodel);
		scan_partialities(crystal_get_reflections(cr), compare,
		                  valid, vals, 0, pmodel);
		reflist_free(compare);

		im_moved = *image;
		shift_parameter(&im_moved, refine, +incr_val);
		compare = find_intersections(&im_moved, cr, pmodel);
		scan_partialities(crystal_get_reflections(cr), compare,
		                  valid, vals, 2, pmodel);
		reflist_free(compare);

	}
}
예제 #7
0
void SimpleShell::calc_thermistor_command( string parameters, StreamOutput *stream)
{
    string s = shift_parameter( parameters );
    int saveto= -1;
    // see if we have -sn as first argument
    if(s.find("-s", 0, 2) != string::npos) {
        // save the results to thermistor n
        saveto= strtol(s.substr(2).c_str(), nullptr, 10);
    }else{
        parameters= s;
    }

    std::vector<float> trl= parse_number_list(parameters.c_str());
    if(trl.size() == 6) {
        // calculate the coefficients
        float c1, c2, c3;
        std::tie(c1, c2, c3) = Thermistor::calculate_steinhart_hart_coefficients(trl[0], trl[1], trl[2], trl[3], trl[4], trl[5]);
        stream->printf("Steinhart Hart coefficients:  I%1.18f J%1.18f K%1.18f\n", c1, c2, c3);
        if(saveto == -1) {
            stream->printf("  Paste the above in the M305 S0 command, then save with M500\n");
        }else{
            char buf[80];
            int n = snprintf(buf, sizeof(buf), "M305 S%d I%1.18f J%1.18f K%1.18f", saveto, c1, c2, c3);
            string g(buf, n);
            Gcode gcode(g, &(StreamOutput::NullStream));
            THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode );
            stream->printf("  Setting Thermistor %d to those settings, save with M500\n", saveto);
        }

    }else{
        // give help
        stream->printf("Usage: calc_thermistor T1,R1,T2,R2,T3,R3\n");
    }
}
예제 #8
0
파일: Player.cpp 프로젝트: arms22/Smoothie
// When a new line is received, check if it is a command, and if it is, act upon it
void Player::on_console_line_received( void *argument )
{
    if(THEKERNEL->is_halted()) return; // if in halted state ignore any commands

    SerialMessage new_message = *static_cast<SerialMessage *>(argument);

    // ignore comments and blank lines and if this is a G code then also ignore it
    char first_char = new_message.message[0];
    if(strchr(";( \n\rGMTN", first_char) != NULL) return;

    string possible_command = new_message.message;
    string cmd = shift_parameter(possible_command);

    //new_message.stream->printf("Received %s\r\n", possible_command.c_str());

    // Act depending on command
    if (cmd == "play"){
        this->play_command( possible_command, new_message.stream );
    }else if (cmd == "progress"){
        this->progress_command( possible_command, new_message.stream );
    }else if (cmd == "abort") {
        this->abort_command( possible_command, new_message.stream );
    }else if (cmd == "suspend") {
        this->suspend_command( possible_command, new_message.stream );
    }else if (cmd == "resume") {
        this->resume_command( possible_command, new_message.stream );
    }
}
예제 #9
0
// When a new line is received, check if it is a command, and if it is, act upon it
void Player::on_console_line_received( void *argument )
{
    if(THEKERNEL->is_halted()) return; // if in halted state ignore any commands

    SerialMessage new_message = *static_cast<SerialMessage *>(argument);

    string possible_command = new_message.message;

    // ignore anything that is not lowercase or a letter
    if(possible_command.empty() || !islower(possible_command[0]) || !isalpha(possible_command[0])) {
        return;
    }

    string cmd = shift_parameter(possible_command);

    //new_message.stream->printf("Received %s\r\n", possible_command.c_str());

    // Act depending on command
    if (cmd == "play"){
        this->play_command( possible_command, new_message.stream );
    }else if (cmd == "progress"){
        this->progress_command( possible_command, new_message.stream );
    }else if (cmd == "abort") {
        this->abort_command( possible_command, new_message.stream );
    }else if (cmd == "suspend") {
        this->suspend_command( possible_command, new_message.stream );
    }else if (cmd == "resume") {
        this->resume_command( possible_command, new_message.stream );
    }
}
예제 #10
0
void Player::progress_command( string parameters, StreamOutput* stream ){

    // get options
    string options           = shift_parameter( parameters );

    if(!playing_file) {
        stream->printf("Not currently playing\r\n");
        return;
    }

    if(file_size > 0) {
        unsigned long est= 0;
        if(this->elapsed_secs > 10) {
            unsigned long bytespersec= played_cnt / this->elapsed_secs;
            if(bytespersec > 0)
                est= (file_size - played_cnt) / bytespersec;
        }

        unsigned int pcnt= (file_size - (file_size - played_cnt)) * 100 / file_size;
        // If -b or -B is passed, report in the format used by Marlin and the others.
        if ( options.find_first_of("Bb") == string::npos ){
            stream->printf("%u %% complete, elapsed time: %lu s", pcnt, this->elapsed_secs);
            if(est > 0){
                stream->printf(", est time: %lu s",  est);
            }
            stream->printf("\r\n");
        }else{
            stream->printf("SD printing byte %lu/%lu\r\n", played_cnt, file_size);
        }

    }else{
        stream->printf("File size is unknown\r\n");
    }
}
예제 #11
0
// show free memory
void SimpleShell::mem_command( string parameters, StreamOutput* stream){
    bool verbose= shift_parameter( parameters ).find_first_of("Vv") != string::npos ;
    unsigned long heap= (unsigned long)_sbrk(0);
    unsigned long m= g_maximumHeapAddress - heap;
    stream->printf("Unused Heap: %lu bytes\r\n", m);

    heapWalk(stream, verbose);
}
예제 #12
0
// used to test out the get public data events for switch
void SimpleShell::switch_command( string parameters, StreamOutput *stream)
{
    string type = shift_parameter( parameters );
    string value = shift_parameter( parameters );
    bool ok = false;
    if(value == "on" || value == "off") {
        bool b = value == "on";
        ok = PublicData::set_value( switch_checksum, get_checksum(type), state_checksum, &b );
    } else {
        float v = strtof(value.c_str(), NULL);
        ok = PublicData::set_value( switch_checksum, get_checksum(type), value_checksum, &v );
    }
    if (ok) {
        stream->printf("switch %s set to: %s\r\n", type.c_str(), value.c_str());
    } else {
        stream->printf("%s is not a known switch device\r\n", type.c_str());
    }
}
예제 #13
0
// Play a gcode file by considering each line as if it was received on the serial console
void SimpleShell::play_command( string parameters, StreamOutput* stream ){
    
    // Get filename
    string filename          = this->absolute_from_relative(shift_parameter( parameters ));
    string options           = shift_parameter( parameters );
    
    this->current_file_handler = fopen( filename.c_str(), "r");
    if(this->current_file_handler == NULL)
    {
    	stream->printf("File not found: %s\r\n", filename.c_str());
    	return;
    }
    this->playing_file = true;
    if( options.find_first_of("Qq") == string::npos ){
        this->current_stream = stream;
    }else{
        this->current_stream = new StreamOutput();
    }
}
예제 #14
0
// When a new line is received, check if it is a command, and if it is, act upon it
void SimpleShell::on_console_line_received( void *argument )
{
    SerialMessage new_message = *static_cast<SerialMessage *>(argument);
    string possible_command = new_message.message;

    // ignore anything that is not lowercase or a $ as it is not a command
    if(possible_command.size() == 0 || (!islower(possible_command[0]) && possible_command[0] != '$')) {
        return;
    }

    // it is a grbl compatible command
    if(possible_command[0] == '$' && possible_command.size() >= 2) {
        switch(possible_command[1]) {
            case 'G':
                // issue get state
                get_command("state", new_message.stream);
                break;

            case 'X':
                THEKERNEL->call_event(ON_HALT, (void *)1); // clears on_halt
                new_message.stream->printf("[Caution: Unlocked]\n");
                break;

            case '#':
                grblDP_command("", new_message.stream);
                break;

            case 'H':
                if(THEKERNEL->is_grbl_mode()) {
                    // issue G28.2 which is force homing cycle
                    Gcode gcode("G28.2", new_message.stream);
                    THEKERNEL->call_event(ON_GCODE_RECEIVED, &gcode);
                }else{
                    new_message.stream->printf("error:only supported in GRBL mode\n");
                }
                break;

            default:
                new_message.stream->printf("error:Invalid statement\n");
                break;
        }

    }else{

        //new_message.stream->printf("Received %s\r\n", possible_command.c_str());
        string cmd = shift_parameter(possible_command);

        // find command and execute it
        if(!parse_command(cmd.c_str(), possible_command, new_message.stream)) {
            new_message.stream->printf("error:Unsupported command\n");
        }
    }
}
예제 #15
0
// Write the specified setting to the specified ConfigSource
void Configurator::config_set_command( string parameters, StreamOutput* stream ){
    string source = shift_parameter(parameters);
    string setting = shift_parameter(parameters);
    string value = shift_parameter(parameters);
    if (value == "") {
        value = setting;
        setting = source;
        source = "";
        this->kernel->config->set_string(setting, value);
        stream->printf( "live: %s has been set to %s\r\n", setting.c_str(), value.c_str() );
    } else {
        uint16_t source_checksum = get_checksum(source);
        for(int i=0; i < this->kernel->config->config_sources.size(); i++){
            if( this->kernel->config->config_sources[i]->is_named(source_checksum) ){
                this->kernel->config->config_sources[i]->write(setting, value);
                stream->printf( "%s: %s has been set to %s\r\n", source.c_str(), setting.c_str(), value.c_str() );
                break;
            }
        }
    }
}
예제 #16
0
static void calc_either_side(Crystal *cr, double incr_val,
                             int *valid, long double *vals[3], int refine,
                             PartialityModel pmodel)
{
	RefList *compare;
	struct image *image = crystal_get_image(cr);
	struct image im_moved;

	im_moved = *image;
	shift_parameter(&im_moved, refine, -incr_val);
	compare = find_intersections(&im_moved, cr, pmodel);
	scan_partialities(crystal_get_reflections(cr), compare,
	                  valid, vals, 0);
	reflist_free(compare);

	im_moved = *image;
	shift_parameter(&im_moved, refine, +incr_val);
	compare = find_intersections(&im_moved, cr, pmodel);
	scan_partialities(crystal_get_reflections(cr), compare,
	                  valid, vals, 2);
	reflist_free(compare);
}
예제 #17
0
// Output a ConfigValue from the specified ConfigSource to the stream
void Configurator::config_get_command( string parameters, StreamOutput* stream ){
    string source = shift_parameter(parameters);
    string setting = shift_parameter(parameters);
    if (setting == "") { // output live setting
        setting = source;
        source = "";
        vector<uint16_t> setting_checksums = get_checksums( setting );
        ConfigValue* cv = this->kernel->config->value(setting_checksums);
        string value = "";
        if(cv->found){ value = cv->as_string(); }
        stream->printf( "live: %s is set to %s\r\n", setting.c_str(), value.c_str() );
    } else { // output setting from specified source
        uint16_t source_checksum = get_checksum( source );
        vector<uint16_t> setting_checksums = get_checksums( setting );
        for(int i=0; i < this->kernel->config->config_sources.size(); i++){
            if( this->kernel->config->config_sources[i]->is_named(source_checksum) ){
                string value = this->kernel->config->config_sources[i]->read(setting_checksums);
                stream->printf( "%s: %s is set to %s\r\n", source.c_str(), setting.c_str(), value.c_str() );
                break;
            }
        }
    }
}
예제 #18
0
// Play a gcode file by considering each line as if it was received on the serial console
void Player::play_command( string parameters, StreamOutput* stream ){

    // Get filename
    this->filename          = this->absolute_from_relative(shift_parameter( parameters ));
    string options           = shift_parameter( parameters );

    this->current_file_handler = fopen( this->filename.c_str(), "r");
    if(this->current_file_handler == NULL){
        stream->printf("File not found: %s\r\n", this->filename.c_str());
        return;
    }

    stream->printf("Playing %s\r\n", this->filename.c_str());

    this->playing_file = true;

    // Do not output to any stream if we were passed the -q ( quiet ) option
    if( options.find_first_of("Qq") == string::npos ){
        this->current_stream = stream;
    }else{
        this->current_stream = &(StreamOutput::NullStream);
    }

    // get size of file
    int result = fseek(this->current_file_handler, 0, SEEK_END);
    if (0 != result){
            stream->printf("WARNING - Could not get file size\r\n");
            file_size= 0;
    }else{
            file_size= ftell(this->current_file_handler);
            fseek(this->current_file_handler, 0, SEEK_SET);
            stream->printf("  File size %ld\r\n", file_size);
    }
    this->played_cnt= 0;
    this->elapsed_secs= 0;
}
예제 #19
0
// Write the specified setting to the specified ConfigSource
void Configurator::config_set_command( string parameters, StreamOutput *stream )
{
    string source = shift_parameter(parameters);
    string setting = shift_parameter(parameters);
    string value = shift_parameter(parameters);
    if(source.empty() || setting.empty() || value.empty()) {
        stream->printf( "Usage: config-set source setting value # where source is sd, setting is the key and value is the new value\r\n" );
        return;
    }

    uint16_t source_checksum = get_checksum(source);
    for(unsigned int i = 0; i < THEKERNEL->config->config_sources.size(); i++) {
        if( THEKERNEL->config->config_sources[i]->is_named(source_checksum) ) {
            if(THEKERNEL->config->config_sources[i]->write(setting, value)) {
                stream->printf( "%s: %s has been set to %s\r\n", source.c_str(), setting.c_str(), value.c_str() );
            } else {
                stream->printf( "%s: %s not enough space to overwrite existing key/value\r\n", source.c_str(), setting.c_str() );
            }
            return;
        }
    }
    stream->printf( "%s source does not exist\r\n", source.c_str());

    /* Live setting not really supported anymore as the cache is never left loaded
        if (value == "") {
            if(!THEKERNEL->config->config_cache_loaded) {
                stream->printf( "live: setting not allowed as config cache is not loaded\r\n" );
                return;
            }
            value = setting;
            setting = source;
            source = "";
            THEKERNEL->config->set_string(setting, value);
            stream->printf( "live: %s has been set to %s\r\n", setting.c_str(), value.c_str() );
    */
}
예제 #20
0
// Output a ConfigValue from the specified ConfigSource to the stream
void Configurator::config_get_command( string parameters, StreamOutput *stream )
{
    string source = shift_parameter(parameters);
    string setting = shift_parameter(parameters);
    if (setting == "") { // output settings from the config-cache
        setting = source;
        source = "";
        uint16_t setting_checksums[3];
        get_checksums(setting_checksums, setting );
        THEKERNEL->config->config_cache_load(); // need to load config cache first as it is unloaded after booting
        ConfigValue *cv = THEKERNEL->config->value(setting_checksums);
        if(cv != NULL && cv->found) {
            string value = cv->as_string();
            stream->printf( "cached: %s is set to %s\r\n", setting.c_str(), value.c_str() );
        } else {
            stream->printf( "cached: %s is not in config\r\n", setting.c_str());
        }
        THEKERNEL->config->config_cache_clear();

    } else { // output setting from specified source by parsing the config file
        uint16_t source_checksum = get_checksum( source );
        uint16_t setting_checksums[3];
        get_checksums(setting_checksums, setting );
        for(unsigned int i = 0; i < THEKERNEL->config->config_sources.size(); i++) {
            if( THEKERNEL->config->config_sources[i]->is_named(source_checksum) ) {
                string value = THEKERNEL->config->config_sources[i]->read(setting_checksums);
                if(value.empty()) {
                    stream->printf( "%s: %s is not in config\r\n", source.c_str(), setting.c_str() );
                } else {
                    stream->printf( "%s: %s is set to %s\r\n", source.c_str(), setting.c_str(), value.c_str() );
                }
                break;
            }
        }
    }
}
예제 #21
0
// show free memory
void SimpleShell::mem_command( string parameters, StreamOutput *stream)
{
    bool verbose = shift_parameter( parameters ).find_first_of("Vv") != string::npos ;
    unsigned long heap = (unsigned long)_sbrk(0);
    unsigned long m = g_maximumHeapAddress - heap;
    stream->printf("Unused Heap: %lu bytes\r\n", m);

    uint32_t f = heapWalk(stream, verbose);
    stream->printf("Total Free RAM: %lu bytes\r\n", m + f);

    stream->printf("Free AHB0: %lu, AHB1: %lu\r\n", AHB0.free(), AHB1.free());
    if (verbose) {
        AHB0.debug(stream);
        AHB1.debug(stream);
    }
}
예제 #22
0
void Player::progress_command( string parameters, StreamOutput *stream )
{

    // get options
    string options = shift_parameter( parameters );
    bool sdprinting= options.find_first_of("Bb") != string::npos;

    if(!playing_file && current_file_handler != NULL) {
        if(sdprinting)
            stream->printf("SD printing byte %lu/%lu\r\n", played_cnt, file_size);
        else
            stream->printf("SD print is paused at %lu/%lu\r\n", played_cnt, file_size);
        return;

    } else if(!playing_file) {
        stream->printf("Not currently playing\r\n");
        return;
    }

    if(file_size > 0) {
        unsigned long est = 0;
        if(this->elapsed_secs > 10) {
            unsigned long bytespersec = played_cnt / this->elapsed_secs;
            if(bytespersec > 0)
                est = (file_size - played_cnt) / bytespersec;
        }

        unsigned int pcnt = (file_size - (file_size - played_cnt)) * 100 / file_size;
        // If -b or -B is passed, report in the format used by Marlin and the others.
        if (!sdprinting) {
            stream->printf("file: %s, %u %% complete, elapsed time: %02lu:%02lu:%02lu", this->filename.c_str(), pcnt, this->elapsed_secs / 3600, (this->elapsed_secs % 3600) / 60, this->elapsed_secs % 60);
            if(est > 0) {
                stream->printf(", est time: %02lu:%02lu:%02lu",  est / 3600, (est % 3600) / 60, est % 60);
            }
            stream->printf("\r\n");
        } else {
            stream->printf("SD printing byte %lu/%lu\r\n", played_cnt, file_size);
        }

    } else {
        stream->printf("File size is unknown\r\n");
    }
}
예제 #23
0
// When a new line is received, check if it is a command, and if it is, act upon it
void Configurator::on_console_line_received( void *argument )
{
    SerialMessage new_message = *static_cast<SerialMessage *>(argument);

    // ignore comments and blank lines and if this is a G code then also ignore it
    char first_char = new_message.message[0];
    if(strchr(";( \n\rGMTN", first_char) != NULL) return;

    string possible_command = new_message.message;
    string cmd = shift_parameter(possible_command);

    // Act depending on command
    if (cmd == "config-get"){
        this->config_get_command(  possible_command, new_message.stream );
    } else if (cmd == "config-set"){
        this->config_set_command(  possible_command, new_message.stream );
    } else if (cmd == "config-load"){
        this->config_load_command(  possible_command, new_message.stream );
    }
}
예제 #24
0
// Reload config values from the specified ConfigSource
void Configurator::config_load_command( string parameters, StreamOutput* stream ){
    string source = shift_parameter(parameters);
    if(source == ""){
        this->kernel->config->config_cache_load();
        this->kernel->call_event(ON_CONFIG_RELOAD);
        stream->printf( "Reloaded settings\r\n" );
    } else if(file_exists(source)){
        FileConfigSource fcs(source);
        fcs.transfer_values_to_cache(&this->kernel->config->config_cache);
        this->kernel->call_event(ON_CONFIG_RELOAD);
        stream->printf( "Loaded settings from %s\r\n", source.c_str() );
    } else {
        uint16_t source_checksum = get_checksum(source);
        for(int i=0; i < this->kernel->config->config_sources.size(); i++){
            if( this->kernel->config->config_sources[i]->is_named(source_checksum) ){
                this->kernel->config->config_sources[i]->transfer_values_to_cache(&this->kernel->config->config_cache);
                this->kernel->call_event(ON_CONFIG_RELOAD);
                stream->printf( "Loaded settings from %s\r\n", source.c_str() );
                break;
            }
        }
    }
}
예제 #25
0
// Act upon an ls command
// Convert the first parameter into an absolute path, then list the files in that path
void SimpleShell::ls_command( string parameters, StreamOutput *stream )
{
    string path, opts;
    while(!parameters.empty()) {
        string s = shift_parameter( parameters );
        if(s.front() == '-') {
            opts.append(s);
        } else {
            path = s;
            if(!parameters.empty()) {
                path.append(" ");
                path.append(parameters);
            }
            break;
        }
    }

    path = absolute_from_relative(path);

    DIR *d;
    struct dirent *p;
    d = opendir(path.c_str());
    if (d != NULL) {
        while ((p = readdir(d)) != NULL) {
            stream->printf("%s", lc(string(p->d_name)).c_str());
            if(p->d_isdir) {
                stream->printf("/");
            } else if(opts.find("-s", 0, 2) != string::npos) {
                stream->printf(" %d", p->d_fsize);
            }
            stream->printf("\r\n");
        }
        closedir(d);
    } else {
        stream->printf("Could not open directory %s\r\n", path.c_str());
    }
}
예제 #26
0
void Player::on_gcode_received(void *argument) {
    Gcode *gcode = static_cast<Gcode*>(argument);
    string args= get_arguments(gcode->command);
    if (gcode->has_m) {
        if (gcode->m == 21) { // Dummy code; makes Octoprint happy -- supposed to initialize SD card
            gcode->mark_as_taken();
            gcode->stream->printf("SD card ok\r\n");

        }else if (gcode->m == 23) { // select file
            gcode->mark_as_taken();
            // Get filename
            this->filename= "/sd/" + this->absolute_from_relative(shift_parameter( args ));
            this->current_stream = &(StreamOutput::NullStream);

            if(this->current_file_handler != NULL) {
                this->playing_file = false;
                fclose(this->current_file_handler);
            }
            this->current_file_handler = fopen( this->filename.c_str(), "r");
            // get size of file
            int result = fseek(this->current_file_handler, 0, SEEK_END);
            if (0 != result){
                    gcode->stream->printf("WARNING - Could not get file size\r\n");
                    file_size= -1;
            }else{
                    file_size= ftell(this->current_file_handler);
                    fseek(this->current_file_handler, 0, SEEK_SET);
            }

            if(this->current_file_handler == NULL){
                gcode->stream->printf("file.open failed: %s\r\n", this->filename.c_str());
            }else{
                gcode->stream->printf("File opened:%s Size:%ld\r\n", this->filename.c_str(),file_size);
                gcode->stream->printf("File selected\r\n");
            }

            this->played_cnt= 0;
            this->elapsed_secs= 0;

        }else if (gcode->m == 24) { // start print
            gcode->mark_as_taken();
            if (this->current_file_handler != NULL) {
                this->playing_file = true;
                this->reply_stream= gcode->stream;
            }

        }else if (gcode->m == 25) { // pause print
            gcode->mark_as_taken();
            this->playing_file = false;

        }else if (gcode->m == 26) { // Reset print. Slightly different than M26 in Marlin and the rest
            gcode->mark_as_taken();
            if(this->current_file_handler != NULL){
                // abort the print
                abort_command("", gcode->stream);

                // reload the last file opened
                this->current_file_handler = fopen( this->filename.c_str(), "r");

                if(this->current_file_handler == NULL){
                    gcode->stream->printf("file.open failed: %s\r\n", this->filename.c_str());
                }else{
                    // get size of file
                    int result = fseek(this->current_file_handler, 0, SEEK_END);
                    if (0 != result){
                            gcode->stream->printf("WARNING - Could not get file size\r\n");
                            file_size= 0;
                    }else{
                            file_size= ftell(this->current_file_handler);
                            fseek(this->current_file_handler, 0, SEEK_SET);
                    }
                }
            }else{
                gcode->stream->printf("No file loaded\r\n");
            }

        }else if (gcode->m == 27) { // report print progress, in format used by Marlin
            gcode->mark_as_taken();
            progress_command("-b", gcode->stream);

        }else if (gcode->m == 32) { // select file and start print
            gcode->mark_as_taken();
            // Get filename
            this->filename= "/sd/" + this->absolute_from_relative(shift_parameter( args ));
            this->current_stream = &(StreamOutput::NullStream);

            if(this->current_file_handler != NULL) {
                this->playing_file = false;
                fclose(this->current_file_handler);
            }

            this->current_file_handler = fopen( this->filename.c_str(), "r");
            if(this->current_file_handler == NULL){
                gcode->stream->printf("file.open failed: %s\r\n", this->filename.c_str());
            }else{
                this->playing_file = true;
            }
        }
    }
}
예제 #27
0
// When a command is received, if it is a Gcode, dispatch it as an object via an event
void GcodeDispatch::on_console_line_received(void *line)
{
    SerialMessage new_message = *static_cast<SerialMessage *>(line);
    string possible_command = new_message.message;

    int ln = 0;
    int cs = 0;

    // just reply ok to empty lines
    if(possible_command.empty()) {
        new_message.stream->printf("ok\r\n");
        return;
    }

try_again:

    char first_char = possible_command[0];
    unsigned int n;

    if(first_char == '$') {
        // ignore as simpleshell will handle it
        return;

    }else if(islower(first_char)) {
        // ignore all lowercase as they are simpleshell commands
        return;
    }

    if ( first_char == 'G' || first_char == 'M' || first_char == 'T' || first_char == 'S' || first_char == 'N' ) {

        //Get linenumber
        if ( first_char == 'N' ) {
            Gcode full_line = Gcode(possible_command, new_message.stream, false);
            ln = (int) full_line.get_value('N');
            int chksum = (int) full_line.get_value('*');

            //Catch message if it is M110: Set Current Line Number
            if ( full_line.has_m ) {
                if ( full_line.m == 110 ) {
                    currentline = ln;
                    new_message.stream->printf("ok\r\n");
                    return;
                }
            }

            //Strip checksum value from possible_command
            size_t chkpos = possible_command.find_first_of("*");
            possible_command = possible_command.substr(0, chkpos);
            //Calculate checksum
            if ( chkpos != string::npos ) {
                for (auto c = possible_command.cbegin(); *c != '*' && c != possible_command.cend(); c++)
                    cs = cs ^ *c;
                cs &= 0xff;  // Defensive programming...
                cs -= chksum;
            }
            //Strip line number value from possible_command
            size_t lnsize = possible_command.find_first_not_of("N0123456789.,- ");
            possible_command = possible_command.substr(lnsize);

        } else {
            //Assume checks succeeded
            cs = 0x00;
            ln = currentline + 1;
        }

        //Remove comments
        size_t comment = possible_command.find_first_of(";(");
        if( comment != string::npos ) {
            possible_command = possible_command.substr(0, comment);
        }

        //If checksum passes then process message, else request resend
        int nextline = currentline + 1;
        if( cs == 0x00 && ln == nextline ) {
            if( first_char == 'N' ) {
                currentline = nextline;
            }

            while(possible_command.size() > 0) {
                // assumes G or M are always the first on the line
                size_t nextcmd = possible_command.find_first_of("GM", 2);
                string single_command;
                if(nextcmd == string::npos) {
                    single_command = possible_command;
                    possible_command = "";
                } else {
                    single_command = possible_command.substr(0, nextcmd);
                    possible_command = possible_command.substr(nextcmd);
                }


                if(!uploading || upload_stream != new_message.stream) {
                    // Prepare gcode for dispatch
                    Gcode *gcode = new Gcode(single_command, new_message.stream);

                    if(THEKERNEL->is_halted()) {
                        // we ignore all commands until M999, unless it is in the exceptions list (like M105 get temp)
                        if(gcode->has_m && gcode->m == 999) {
                            if(THEKERNEL->is_halted()) {
                                THEKERNEL->call_event(ON_HALT, (void *)1); // clears on_halt
                                new_message.stream->printf("WARNING: After HALT you should HOME as position is currently unknown\n");
                            }
                            new_message.stream->printf("ok\n");
                            delete gcode;
                            continue;

                        }else if(!is_allowed_mcode(gcode->m)) {
                            // ignore everything, return error string to host
                            if(THEKERNEL->is_grbl_mode()) {
                                new_message.stream->printf("error:Alarm lock\n");

                            }else{
                                new_message.stream->printf("!!\r\n");
                            }
                            delete gcode;
                            continue;
                        }
                    }

                    if(gcode->has_g) {
                        if(gcode->g == 53) { // G53 makes next movement command use machine coordinates
                            // this is ugly to implement as there may or may not be a G0/G1 on the same line
                            // valid version seem to include G53 G0 X1 Y2 Z3 G53 X1 Y2
                            if(possible_command.empty()) {
                                // use last gcode G1 or G0 if none on the line, and pass through as if it was a G0/G1
                                // TODO it is really an error if the last is not G0 thru G3
                                if(modal_group_1 > 3) {
                                    delete gcode;
                                    new_message.stream->printf("ok - Invalid G53\r\n");
                                    return;
                                }
                                // use last G0 or G1
                                gcode->g= modal_group_1;

                            }else{
                                delete gcode;
                                // extract next G0/G1 from the rest of the line, ignore if it is not one of these
                                gcode = new Gcode(possible_command, new_message.stream);
                                possible_command= "";
                                if(!gcode->has_g || gcode->g > 1) {
                                    // not G0 or G1 so ignore it as it is invalid
                                    delete gcode;
                                    new_message.stream->printf("ok - Invalid G53\r\n");
                                    return;
                                }
                            }
                            // makes it handle the parameters as a machine position
                            THEROBOT->next_command_is_MCS= true;

                        }

                        // remember last modal group 1 code
                        if(gcode->g < 4) {
                            modal_group_1= gcode->g;
                        }
                    }

                    if(gcode->has_m) {
                        switch (gcode->m) {
                            case 28: // start upload command
                                delete gcode;

                                this->upload_filename = "/sd/" + single_command.substr(4); // rest of line is filename
                                // open file
                                upload_fd = fopen(this->upload_filename.c_str(), "w");
                                if(upload_fd != NULL) {
                                    this->uploading = true;
                                    new_message.stream->printf("Writing to file: %s\r\nok\r\n", this->upload_filename.c_str());
                                } else {
                                    new_message.stream->printf("open failed, File: %s.\r\nok\r\n", this->upload_filename.c_str());
                                }

                                // only save stuff from this stream
                                upload_stream= new_message.stream;

                                //printf("Start Uploading file: %s, %p\n", upload_filename.c_str(), upload_fd);
                                continue;

                            case 30: // end of program
                                if(!THEKERNEL->is_grbl_mode()) break; // Special case M30 as it is also delete sd card file so only do this if in grbl mode
                                // fall through to M2
                            case 2:
                                {
                                    modal_group_1= 1; // set to G1
                                    // issue M5 and M9 in case spindle and coolant are being used
                                    Gcode gc1("M5", &StreamOutput::NullStream);
                                    THEKERNEL->call_event(ON_GCODE_RECEIVED, &gc1);
                                    Gcode gc2("M9", &StreamOutput::NullStream);
                                    THEKERNEL->call_event(ON_GCODE_RECEIVED, &gc2);
                                }
                                break;

                            case 112: // emergency stop, do the best we can with this
                                // this is also handled out-of-band (it is now with ^X in the serial driver)
                                // disables heaters and motors, ignores further incoming Gcode and clears block queue
                                THEKERNEL->call_event(ON_HALT, nullptr);
                                THEKERNEL->streams->printf("ok Emergency Stop Requested - reset or M999 required to exit HALT state\r\n");
                                delete gcode;
                                return;

                            case 117: // M117 is a special non compliant Gcode as it allows arbitrary text on the line following the command
                            {    // concatenate the command again and send to panel if enabled
                                string str= single_command.substr(4) + possible_command;
                                PublicData::set_value( panel_checksum, panel_display_message_checksum, &str );
                                delete gcode;
                                new_message.stream->printf("ok\r\n");
                                return;
                            }

                            case 1000: // M1000 is a special command that will pass thru the raw lowercased command to the simpleshell (for hosts that do not allow such things)
                            {
                                // reconstruct entire command line again
                                string str= single_command.substr(5) + possible_command;
                                while(is_whitespace(str.front())){ str= str.substr(1); } // strip leading whitespace

                                delete gcode;

                                if(str.empty()) {
                                    SimpleShell::parse_command("help", "", new_message.stream);

                                }else{
                                    string args= lc(str);
                                    string cmd = shift_parameter(args);
                                    // find command and execute it
                                    if(!SimpleShell::parse_command(cmd.c_str(), args, new_message.stream)) {
                                        new_message.stream->printf("Command not found: %s\n", cmd.c_str());
                                    }
                                }

                                new_message.stream->printf("ok\r\n");
                                return;
                            }

                            case 500: // M500 save volatile settings to config-override
                                THEKERNEL->conveyor->wait_for_idle(); //just to be safe as it can take a while to run
                                //remove(THEKERNEL->config_override_filename()); // seems to cause a hang every now and then
                                __disable_irq();
                                {
                                    FileStream fs(THEKERNEL->config_override_filename());
                                    fs.printf("; DO NOT EDIT THIS FILE\n");
                                    // this also will truncate the existing file instead of deleting it
                                }
                                // replace stream with one that writes to config-override file
                                gcode->stream = new AppendFileStream(THEKERNEL->config_override_filename());
                                // dispatch the M500 here so we can free up the stream when done
                                THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode );
                                delete gcode->stream;
                                delete gcode;
                                __enable_irq();
                                new_message.stream->printf("Settings Stored to %s\r\nok\r\n", THEKERNEL->config_override_filename());
                                continue;

                            case 501: // load config override
                            case 504: // save to specific config override file
                                {
                                    string arg= get_arguments(single_command + possible_command); // rest of line is filename
                                    if(arg.empty()) arg= "/sd/config-override";
                                    else arg= "/sd/config-override." + arg;
                                    //new_message.stream->printf("args: <%s>\n", arg.c_str());
                                    SimpleShell::parse_command((gcode->m == 501) ? "load_command" : "save_command", arg, new_message.stream);
                                }
                                delete gcode;
                                new_message.stream->printf("ok\r\n");
                                return;

                            case 502: // M502 deletes config-override so everything defaults to what is in config
                                remove(THEKERNEL->config_override_filename());
                                delete gcode;
                                new_message.stream->printf("config override file deleted %s, reboot needed\r\nok\r\n", THEKERNEL->config_override_filename());
                                continue;

                            case 503: { // M503 display live settings and indicates if there is an override file
                                FILE *fd = fopen(THEKERNEL->config_override_filename(), "r");
                                if(fd != NULL) {
                                    fclose(fd);
                                    new_message.stream->printf("; config override present: %s\n",  THEKERNEL->config_override_filename());

                                } else {
                                    new_message.stream->printf("; No config override\n");
                                }
                                gcode->add_nl= true;
                                break; // fall through to process by modules
                            }

                        }
                    }

                    //printf("dispatch %p: '%s' G%d M%d...", gcode, gcode->command.c_str(), gcode->g, gcode->m);
                    //Dispatch message!
                    THEKERNEL->call_event(ON_GCODE_RECEIVED, gcode );

                    if (gcode->is_error) {
                        // report error
                        if(THEKERNEL->is_grbl_mode()) {
                            new_message.stream->printf("error: ");
                        }else{
                            new_message.stream->printf("Error: ");
                        }

                        if(!gcode->txt_after_ok.empty()) {
                            new_message.stream->printf("%s\r\n", gcode->txt_after_ok.c_str());
                            gcode->txt_after_ok.clear();

                        }else{
                            new_message.stream->printf("unknown\r\n");
                        }

                        // we cannot continue safely after an error so we enter HALT state
                        new_message.stream->printf("Entering Alarm/Halt state\n");
                        THEKERNEL->call_event(ON_HALT, nullptr);

                    }else{

                        if(gcode->add_nl)
                            new_message.stream->printf("\r\n");

                        if(!gcode->txt_after_ok.empty()) {
                            new_message.stream->printf("ok %s\r\n", gcode->txt_after_ok.c_str());
                            gcode->txt_after_ok.clear();

                        } else {
                            if(THEKERNEL->is_ok_per_line() || THEKERNEL->is_grbl_mode()) {
                                // only send ok once per line if this is a multi g code line send ok on the last one
                                if(possible_command.empty())
                                    new_message.stream->printf("ok\r\n");
                            } else {
                                // maybe should do the above for all hosts?
                                new_message.stream->printf("ok\r\n");
                            }
                        }
                    }

                    delete gcode;

                } else {
                    // we are uploading and it is the upload stream so so save it
                    if(single_command.substr(0, 3) == "M29") {
                        // done uploading, close file
                        fclose(upload_fd);
                        upload_fd = NULL;
                        uploading = false;
                        upload_filename.clear();
                        upload_stream= nullptr;
                        new_message.stream->printf("Done saving file.\r\nok\r\n");
                        continue;
                    }

                    if(upload_fd == NULL) {
                        // error detected writing to file so discard everything until it stops
                        new_message.stream->printf("ok\r\n");
                        continue;
                    }

                    single_command.append("\n");
                    static int cnt = 0;
                    if(fwrite(single_command.c_str(), 1, single_command.size(), upload_fd) != single_command.size()) {
                        // error writing to file
                        new_message.stream->printf("Error:error writing to file.\r\n");
                        fclose(upload_fd);
                        upload_fd = NULL;
                        continue;

                    } else {
                        cnt += single_command.size();
                        if (cnt > 400) {
                            // HACK ALERT to get around fwrite corruption close and re open for append
                            fclose(upload_fd);
                            upload_fd = fopen(upload_filename.c_str(), "a");
                            cnt = 0;
                        }
                        new_message.stream->printf("ok\r\n");
                        //printf("uploading file write ok\n");
                    }
                }
            }

        } else {
            //Request resend
            new_message.stream->printf("rs N%d\r\n", nextline);
        }

    } else if( (n=possible_command.find_first_of("XYZF")) == 0 || (first_char == ' ' && n != string::npos) ) {
        // handle pycam syntax, use last modal group 1 command and resubmit if an X Y Z or F is found on its own line
        char buf[6];
        snprintf(buf, sizeof(buf), "G%d ", modal_group_1);
        possible_command.insert(0, buf);
        goto try_again;

        // Ignore comments and blank lines
    } else if ( first_char == ';' || first_char == '(' || first_char == ' ' || first_char == '\n' || first_char == '\r' ) {
        new_message.stream->printf("ok\r\n");
    }
}
예제 #28
0
// used to test out the get public data events
void SimpleShell::get_command( string parameters, StreamOutput *stream)
{
    string what = shift_parameter( parameters );

    if (what == "temp") {
        struct pad_temperature temp;
        string type = shift_parameter( parameters );
        if(type.empty()) {
            // scan all temperature controls
            std::vector<struct pad_temperature> controllers;
            bool ok = PublicData::get_value(temperature_control_checksum, poll_controls_checksum, &controllers);
            if (ok) {
                for (auto &c : controllers) {
                   stream->printf("%s (%d) temp: %f/%f @%d\r\n", c.designator.c_str(), c.id, c.current_temperature, c.target_temperature, c.pwm);
                }

            } else {
                stream->printf("no heaters found\r\n");
            }

        }else{
            bool ok = PublicData::get_value( temperature_control_checksum, current_temperature_checksum, get_checksum(type), &temp );

            if (ok) {
                stream->printf("%s temp: %f/%f @%d\r\n", type.c_str(), temp.current_temperature, temp.target_temperature, temp.pwm);
            } else {
                stream->printf("%s is not a known temperature device\r\n", type.c_str());
            }
        }

    } else if (what == "fk" || what == "ik") {
        string p= shift_parameter( parameters );
        bool move= false;
        if(p == "-m") {
            move= true;
            p= shift_parameter( parameters );
        }

        std::vector<float> v= parse_number_list(p.c_str());
        if(p.empty() || v.size() < 1) {
            stream->printf("error:usage: get [fk|ik] [-m] x[,y,z]\n");
            return;
        }

        float x= v[0];
        float y= (v.size() > 1) ? v[1] : x;
        float z= (v.size() > 2) ? v[2] : y;

        if(what == "fk") {
            // do forward kinematics on the given actuator position and display the cartesian coordinates
            ActuatorCoordinates apos{x, y, z};
            float pos[3];
            THEKERNEL->robot->arm_solution->actuator_to_cartesian(apos, pos);
            stream->printf("cartesian= X %f, Y %f, Z %f, Steps= A %lu, B %lu, C %lu\n",
                pos[0], pos[1], pos[2],
                lroundf(x*THEKERNEL->robot->actuators[0]->get_steps_per_mm()),
                lroundf(y*THEKERNEL->robot->actuators[1]->get_steps_per_mm()),
                lroundf(z*THEKERNEL->robot->actuators[2]->get_steps_per_mm()));
            x= pos[0];
            y= pos[1];
            z= pos[2];

        }else{
            // do inverse kinematics on the given cartesian position and display the actuator coordinates
            float pos[3]{x, y, z};
            ActuatorCoordinates apos;
            THEKERNEL->robot->arm_solution->cartesian_to_actuator(pos, apos);
            stream->printf("actuator= A %f, B %f, C %f\n", apos[0], apos[1], apos[2]);
        }

        if(move) {
            // move to the calculated, or given, XYZ
            char cmd[64];
            snprintf(cmd, sizeof(cmd), "G53 G0 X%f Y%f Z%f", x, y, z);
            struct SerialMessage message;
            message.message = cmd;
            message.stream = &(StreamOutput::NullStream);
            THEKERNEL->call_event(ON_CONSOLE_LINE_RECEIVED, &message );
            THEKERNEL->conveyor->wait_for_empty_queue();
        }

   } else if (what == "pos") {
        // convenience to call all the various M114 variants
        char buf[64];
        THEKERNEL->robot->print_position(0, buf, sizeof buf); stream->printf("last %s\n", buf);
        THEKERNEL->robot->print_position(1, buf, sizeof buf); stream->printf("realtime %s\n", buf);
        THEKERNEL->robot->print_position(2, buf, sizeof buf); stream->printf("%s\n", buf);
        THEKERNEL->robot->print_position(3, buf, sizeof buf); stream->printf("%s\n", buf);
        THEKERNEL->robot->print_position(4, buf, sizeof buf); stream->printf("%s\n", buf);
        THEKERNEL->robot->print_position(5, buf, sizeof buf); stream->printf("%s\n", buf);

    } else if (what == "wcs") {
        // print the wcs state
        std::vector<Robot::wcs_t> v= THEKERNEL->robot->get_wcs_state();
        char current_wcs= std::get<0>(v[0]);
        stream->printf("current WCS: %s\n", wcs2gcode(current_wcs).c_str());
        int n= std::get<1>(v[0]);
        for (int i = 1; i <= n; ++i) {
            stream->printf("%s: %1.4f, %1.4f, %1.4f\n", wcs2gcode(i-1).c_str(), std::get<0>(v[i]), std::get<1>(v[i]), std::get<2>(v[i]));
        }

        stream->printf("G92: %1.4f, %1.4f, %1.4f\n", std::get<0>(v[n+1]), std::get<1>(v[n+1]), std::get<2>(v[n+1]));
        stream->printf("ToolOffset: %1.4f, %1.4f, %1.4f\n", std::get<0>(v[n+2]), std::get<1>(v[n+2]), std::get<2>(v[n+2]));

    } else if (what == "state") {
        // also $G
        // [G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 F0.]
        stream->printf("[G%d %s G%d G%d G%d G94 M0 M5 M9 T%d F%1.1f]\n",
            THEKERNEL->gcode_dispatch->get_modal_command(),
            wcs2gcode(THEKERNEL->robot->get_current_wcs()).c_str(),
            THEKERNEL->robot->plane_axis_0 == X_AXIS && THEKERNEL->robot->plane_axis_1 == Y_AXIS && THEKERNEL->robot->plane_axis_2 == Z_AXIS ? 17 :
              THEKERNEL->robot->plane_axis_0 == X_AXIS && THEKERNEL->robot->plane_axis_1 == Z_AXIS && THEKERNEL->robot->plane_axis_2 == Y_AXIS ? 18 :
              THEKERNEL->robot->plane_axis_0 == Y_AXIS && THEKERNEL->robot->plane_axis_1 == Z_AXIS && THEKERNEL->robot->plane_axis_2 == X_AXIS ? 19 : 17,
            THEKERNEL->robot->inch_mode ? 20 : 21,
            THEKERNEL->robot->absolute_mode ? 90 : 91,
            get_active_tool(),
            THEKERNEL->robot->get_feed_rate());

    } else {
        stream->printf("error:unknown option %s\n", what.c_str());
    }
}
예제 #29
0
// Output the contents of a file, first parameter is the filename, second is the limit ( in number of lines to output )
void SimpleShell::cat_command( string parameters, StreamOutput *stream )
{
    // Get parameters ( filename and line limit )
    string filename          = absolute_from_relative(shift_parameter( parameters ));
    string limit_parameter   = shift_parameter( parameters );
    int limit = -1;
    int delay= 0;
    bool send_eof= false;
    if ( limit_parameter == "-d" ) {
        string d= shift_parameter( parameters );
        char *e = NULL;
        delay = strtol(d.c_str(), &e, 10);
        if (e <= d.c_str()) {
            delay = 0;

        } else {
            send_eof= true; // we need to terminate file send with an eof
        }

    }else if ( limit_parameter != "" ) {
        char *e = NULL;
        limit = strtol(limit_parameter.c_str(), &e, 10);
        if (e <= limit_parameter.c_str())
            limit = -1;
    }

    // we have been asked to delay before cat, probably to allow time to issue upload command
    if(delay > 0) {
        safe_delay(delay*1000);
    }

    // Open file
    FILE *lp = fopen(filename.c_str(), "r");
    if (lp == NULL) {
        stream->printf("File not found: %s\r\n", filename.c_str());
        return;
    }
    string buffer;
    int c;
    int newlines = 0;
    int linecnt = 0;
    // Print each line of the file
    while ((c = fgetc (lp)) != EOF) {
        buffer.append((char *)&c, 1);
        if ( c == '\n' || ++linecnt > 80) {
            if(c == '\n') newlines++;
            stream->puts(buffer.c_str());
            buffer.clear();
            if(linecnt > 80) linecnt = 0;
            // we need to kick things or they die
            THEKERNEL->call_event(ON_IDLE);
        }
        if ( newlines == limit ) {
            break;
        }
    };
    fclose(lp);

    if(send_eof) {
        stream->puts("\032"); // ^Z terminates the upload
    }
}
예제 #30
0
// Delete a file
void SimpleShell::rm_command( string parameters, StreamOutput *stream )
{
    const char *fn = absolute_from_relative(shift_parameter( parameters )).c_str();
    int s = remove(fn);
    if (s != 0) stream->printf("Could not delete %s \r\n", fn);
}