Thanks to visit codestin.com
Credit goes to github.com

Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 11 additions & 2 deletions apps/micro_ros/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,7 @@ raros_interfaces__msg__StepperFeedback feedback_msg;
raros_interfaces__msg__StepperParameters parameters_msg;

bool move_cancelled = false;
bool hold_power = false;
int steps_per_revolution = 1600 * 4;

// default initialization
Expand All @@ -71,9 +72,11 @@ void stop_callback(const void *msgin) {
void parameters_callback(const void *msgin) {
const auto *parameters = (const raros_interfaces__msg__StepperParameters *) msgin;
publish_log("received params steps_per_revolution: " + String(parameters->steps_per_revolution) +
", micro_steps: " + String(parameters->micro_steps));
", micro_steps: " + String(parameters->micro_steps) +
", hold_power: " + String(parameters->hold_power));

steps_per_revolution = parameters->steps_per_revolution * parameters->micro_steps;
hold_power = parameters->hold_power;
motor_left = Stepper(steps_per_revolution, STEP_PIN_MOTOR_LEFT, DIR_PIN_MOTOR_LEFT);
motor_right = Stepper(steps_per_revolution, STEP_PIN_MOTOR_RIGHT, DIR_PIN_MOTOR_RIGHT);
}
Expand Down Expand Up @@ -192,12 +195,18 @@ void destroy_entities() {
RCSOFTCHECK(rclc_executor_fini(&executor_stop));
RCSOFTCHECK(rcl_node_fini(&node));
RCSOFTCHECK(rclc_support_fini(&support));

digitalWrite(MOTOR_POWER_SUPPLY_PIN, LOW);
}

// Stepper functions
// -----------------------------------------------------------------------------
void toggle_power_supply(bool on) {
digitalWrite(MOTOR_POWER_SUPPLY_PIN, on ? HIGH : LOW);
if (on) {
digitalWrite(MOTOR_POWER_SUPPLY_PIN, HIGH);
} else if (!hold_power) {
digitalWrite(MOTOR_POWER_SUPPLY_PIN, LOW);
}
}

void stop_move() {
Expand Down
3 changes: 2 additions & 1 deletion apps/ros2/src/raros/config/params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,12 @@ raros:
active: true
steps_per_revolution: 1600
micro_steps: 4
hold_power: false
wheel:
distance: 22.0
radius: 4.21
default_speed:
linear: 30
rotation: 15
turn_with_radius: 40
turn_on_spot: 20
turn_on_spot: 30
7 changes: 5 additions & 2 deletions apps/ros2/src/raros/raros/navigation/navigation.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
class Navigation(Node):
def __init__(self):
super().__init__('navigation')
(self.active, self.steps_per_revolution, self.micro_steps,
(self.active, self.steps_per_revolution, self.micro_steps, self.hold_power,
self.wheel_distance, self.wheel_radius, self.default_speed_linear, self.default_speed_rotation,
self.default_speed_turn_with_radius, self.default_speed_turn_on_spot) = self.init_params()
if not self.active:
Expand All @@ -37,6 +37,7 @@ def init_params(self):
self.declare_parameter('active', True)
self.declare_parameter('steps_per_revolution', 1600)
self.declare_parameter('micro_steps', 4)
self.declare_parameter('hold_power', False)
self.declare_parameter('wheel.distance', 22.0)
self.declare_parameter('wheel.radius', 4.2)
self.declare_parameter('default_speed.linear', 30)
Expand All @@ -46,6 +47,7 @@ def init_params(self):
active = self.get_parameter('active').get_parameter_value().bool_value
steps_per_revolution = self.get_parameter('steps_per_revolution').get_parameter_value().integer_value
micro_steps = self.get_parameter('micro_steps').get_parameter_value().integer_value
hold_power = self.get_parameter('hold_power').get_parameter_value().bool_value
wheel_distance = self.get_parameter('wheel.distance').get_parameter_value().double_value
wheel_radius = self.get_parameter('wheel.radius').get_parameter_value().double_value
default_speed_linear = self.get_parameter('default_speed.linear').get_parameter_value().integer_value
Expand All @@ -54,14 +56,15 @@ def init_params(self):
'default_speed.turn_with_radius').get_parameter_value().integer_value
default_speed_turn_on_spot = self.get_parameter(
'default_speed.turn_on_spot').get_parameter_value().integer_value
return (active, steps_per_revolution, micro_steps, wheel_distance, wheel_radius,
return (active, steps_per_revolution, micro_steps, hold_power, wheel_distance, wheel_radius,
default_speed_linear, default_speed_rotation, default_speed_turn_with_radius,
default_speed_turn_on_spot)

def propagate_parameters(self):
stepper_parameters_msg = StepperParameters()
stepper_parameters_msg.steps_per_revolution = self.steps_per_revolution
stepper_parameters_msg.micro_steps = self.micro_steps
stepper_parameters_msg.hold_power = self.hold_power
self.stepper_parameters_publisher.publish(stepper_parameters_msg)

def stop_callback(self, request, response):
Expand Down
3 changes: 2 additions & 1 deletion apps/ros2/src/raros_interfaces/msg/StepperParameters.msg
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
int32 steps_per_revolution
int32 micro_steps
int32 micro_steps
bool hold_power