Why is rosserial skipping part of the code?
I am currently using rosserial to interface with my arduino, but it seems like that is it skipping some parts of the code?
This is my main.ino
#include "speed_profile.h"
void setup() {
// put your setup code here, to run once:
output_pin_setup();
cli();
timer1_setup();
sei();
}
void loop()
{
int motor_steps = 23400;//-9600; //23400 - 100%
// Accelration to use.
int motor_acceleration = 500;//500;
// Deceleration to use.
int motor_deceleration = 500;//500;
// Speed to use.
int motor_speed = 1000; // 1000
init_tipper_position();
compute_speed_profile(motor_steps, motor_acceleration, motor_deceleration, motor_speed);
}
The function init_tipper_position()
initializes the position of my motor, but for some reason is this function ignored.
It never gets executed which i can feel on the motor as i am able to move it due to missing en_pin being high.
The code jumps directly to compute_speed_profile()
when i start rosserial, and wait for me to publish something on to the topic it subscribes, and moves when I provide it the thing it needs.
how come is it skipping the prior function?
This is the init_tipper_position()
function
void init_tipper_position()
{
digitalWrite(en_pin, HIGH);
delay(1);
digitalWrite(dir_pin, LOW);
delay(1);
int decrement = 0;
while((PINB & (1 << 2)))
{
decrement++;
digitalWrite(step_pin, HIGH);
delayMicroseconds(600);
digitalWrite(step_pin, LOW);
delayMicroseconds(600);
}
digitalWrite(en_pin, LOW);
}
The other function declarations can be seen in the attached .
.cpp file
#include "speed_profile.h"
volatile speed_profile profile;
ros::NodeHandle nh;
std_msgs::Int16 status_step_count;
std_msgs::Int16 status_tipper_availability;
ros::Publisher chatter_status("tipper_status", &status_step_count);
ros::Publisher chatter_availabilty("tipper_availability", &status_tipper_availability);
volatile bool global_state = false;
bool moved_to_position = true;
int received_data = 0;
void call_back_control( const std_msgs::Empty & msg)
{
global_state = true;
// For HMI
received_data = (10 *23400.0)/100.0; // Converts input to motor_steps.
}
ros::Subscriber<std_msgs::Empty> sub_control("tipper_control", &call_back_control );
void output_pin_setup()
{
pinMode(en_pin, OUTPUT);
pinMode(dir_pin, OUTPUT);
pinMode(step_pin, OUTPUT);
pinMode(slot_sensor_pin,INPUT_PULLUP);
nh.initNode();
nh.advertise(chatter_status);
nh.advertise(chatter_availabilty);
nh.subscribe(sub_control);
//nh.subscribe(sub_command);
profile.current_step_position = 0;
delay(10);
nh.getHardware()->setBaud(57600);
}
void init_tipper_position()
{
digitalWrite(en_pin, HIGH);
delay(1);
digitalWrite(dir_pin, LOW);
delay(1);
int decrement = 0;
while((PINB & (1 << 2)))
{
decrement++;
digitalWrite(step_pin, HIGH);
delayMicroseconds(600);
digitalWrite(step_pin, LOW);
delayMicroseconds(600);
}
digitalWrite(en_pin, LOW);
}
void timer1_setup()
{
// Tells what part of speed ramp we are in.
profile.run_state = STOP;
// Timer/Counter 1 in mode 4 CTC (Not running).
TCCR1B = (1 << WGM12);
// Timer/Counter 1 Output Compare A Match Interrupt enable.
TIMSK1 = (1 << OCIE1A);
}
void computation_of_speed_profile(signed int motor_steps, unsigned int motor_accel, unsigned int motor_decel, unsigned int motor_speed)
{
unsigned int steps_to_speed; // Steps required to achieve the the speed desired
unsigned int acceleration_step_limit; // If desired speed is not achieved, will this variable contain step_limit to when to stop accelerating.
// If moving only 1 step.
if (motor_steps == 1)
{
// Move one step
profile.accel_count = -1;
// in DECEL state.
profile.run_state = DECEL;
// Just a short delay so main() can act on 'running'.
profile.first_step_delay = 1000;
OCR1A = 10;
// Run Timer/Counter 1 with prescaler = 8.
TCCR1B |= ((0 << CS12) | (1 << CS11) | (0 << CS10));
}
else if (motor_steps != 0)
{
// Set max speed limit, by calc min_delay to use in timer.
// min_delay = (alpha / tt)/ w
profile.min_time_delay = A_T_x100 / motor_speed;
// Set accelration ...