Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Revert "Revert "Mirte master namespace-able"" #14

Merged
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
48 changes: 24 additions & 24 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,26 +1,26 @@
# API

The motors are controlled with PWM as as service. By default the topic published by the ROS diff_drive_controller (/mobile_base_controller/cmd_vel) will call that service. One has to disable the ROS diff_drive_controller () to manually set the PWM signal by using the service (eg from commandline).
The motors are controlled with PWM as as service. By default the topic published by the ROS diff_drive_controller (`mobile_base_controller/cmd_vel`) will call that service. One has to disable the ROS diff_drive_controller () to manually set the PWM signal by using the service (eg from commandline).
Currently, the default parameters are set to use the Mirte Arduino-nano PCB.

## Subscribed Topics
/mobile_base_controller/cmd_vel (geometry_msgs/Twist)
`mobile_base_controller/cmd_vel` (geometry_msgs/Twist)

## Published Topics
Topics published to depend on the parameters given.

/mirte/<name>_distance (sensor_msgs/Range)
/mirte/<name>_encoder (mirte_msgs/Encoder)
/mirte/<name>_intensity (mirte_msgs/Intensity)
`mirte/<name>_distance` (sensor_msgs/Range)
`mirte/<name>_encoder` (mirte_msgs/Encoder)
`mirte/<name>_intensity` (mirte_msgs/Intensity)

## Services
/mirte_navigation/move
/mirte_navigation/turn
/mirte_pymata/set_<name>_motor_pwm
/mirte/get_pin_value
/mirte/set_pin_mode
/mirte/set_pin_value
/mirte_service_api/get_<topic_name>
`mirte_navigation/move`
`mirte_navigation/turn`
`mirte_pymata/set_<name>_motor_pwm`
`mirte/get_pin_value`
`mirte/set_pin_mode`
`mirte/set_pin_value`
`mirte_service_api/get_<topic_name>`


## Parameters
Expand All @@ -33,26 +33,26 @@ device/mirte/dev (string, default: "/dev/ttyUSB0")
The linux device name of the board.

#### Distance sensor
distance/<name>_distance/dev (string, default: "mirte")
distance/<name>_distance/frequency (int, default: 10)
`distance/<name>_distance/dev` (string, default: "mirte")
`distance/<name>_distance/frequency` (int, default: 10)
The frequency to publish new sensor data
distance/<name>_distance/pin (array)
`distance/<name>_distance/pin` (array)
The (arduino/stm32) pins it is connected to [trigger-pin, echo-pin] (eg [8. 13])

#### Encoder sensor
Note: the encoder sensor does not have a frequency since it uses the interrupt pins
encoder/<name>_encoder/device (string, default: "mirte")
encoder/<name>_encoder/pin (int)
encoder/<name>_encoder/ticks_per_wheel (int, default: 20)
`encoder/<name>_encoder/device` (string, default: "mirte")
`encoder/<name>_encoder/pin` (int)
`encoder/<name>_encoder/ticks_per_wheel` (int, default: 20)

#### Intensity sensor
intensity/<name>_intensity/device (string, default: "mirte")
intensity/<name>_intensity/frequency (int, default: 10)
intensity/<name>_intensity/pin (int)
`intensity/<name>_intensity/device` (string, default: "mirte")
`intensity/<name>_intensity/frequency` (int, default: 10)
`intensity/<name>_intensity/pin` (int)

#### Motor settings
motor/<name>_motor/device (string, default: "mirte")
motor/<name>_motor/pin (array)
`motor/<name>_motor/device` (string, default: "mirte")
`motor/<name>_motor/pin` (array)
The (arduino/stm32) pins the motor (h-bridge) is connected to. When using 2 pins per motor it will assume MX1919 (both PWM signals). When using 3 pins it will assume L298N (1 PWM, 2 non-PWM)


Expand All @@ -72,4 +72,4 @@ clang-format --Werror ./**/**.cpp -style=llvm -i
```

# Required packages Telemetrix
Requires https://github.com/mirte-robot/tmx-pico-aio.git to be installed ( ```pip install git+https://github.com/mirte-robot/tmx-pico-aio.git``` ) for the Pico and https://github.com/mirte-robot/telemetrix-aio.git for the STM32 and Arduino Nano (```pip install git+https://github.com/mirte-robot/telemetrix-aio.git```).
Requires https://github.com/mirte-robot/tmx-pico-aio.git to be installed ( ```pip install git+https://github.com/mirte-robot/tmx-pico-aio.git``` ) for the Pico and https://github.com/mirte-robot/telemetrix-aio.git for the STM32 and Arduino Nano (```pip install git+https://github.com/mirte-robot/telemetrix-aio.git```).
24 changes: 11 additions & 13 deletions mirte_control/mirte_base_control/include/my_robot_hw_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,8 @@
#include <mutex>
#include <thread>
// const unsigned int NUM_JOINTS = 4;
const auto service_format = "/mirte/set_%s_speed";
const auto encoder_format = "/mirte/encoder/%s";
const auto service_format = "mirte/set_%s_speed";
const auto encoder_format = "mirte/encoder/%s";
const auto max_speed = 100; // Quick fix hopefully for power dip.

bool equal_gains(control_toolbox::Pid::Gains lhs,
Expand Down Expand Up @@ -239,7 +239,7 @@ void MyRobotHWInterface::init_service_clients() {

unsigned int detect_joints(ros::NodeHandle &nh) {
std::string type;
nh.param<std::string>("/mobile_base_controller/type", type, "");
nh.param<std::string>("mobile_base_controller/type", type, "");
if (type.rfind("mecanum", 0) == 0) { // starts with mecanum
return 4;
} else if (type.rfind("diff", 0) == 0) { // starts with diff
Expand All @@ -256,13 +256,13 @@ MyRobotHWInterface::MyRobotHWInterface()
"start", &MyRobotHWInterface::start_callback, this)),
stop_srv_(nh.advertiseService("stop", &MyRobotHWInterface::stop_callback,
this)) {
private_nh.param<double>("/mobile_base_controller/wheel_radius",
_wheel_diameter, 0.06);
nh.param<double>("mobile_base_controller/wheel_radius", _wheel_diameter,
0.06);
_wheel_diameter *= 2; // convert from radius to diameter
private_nh.param<double>("/mobile_base_controller/max_speed", _max_speed,
2.0); // TODO: unused
private_nh.param<double>("/mobile_base_controller/ticks", ticks, 40.0);
this->NUM_JOINTS = detect_joints(private_nh);
nh.param<double>("mobile_base_controller/max_speed", _max_speed,
2.0); // TODO: unused
nh.param<double>("mobile_base_controller/ticks", ticks, 40.0);
this->NUM_JOINTS = detect_joints(nh);
if (this->NUM_JOINTS > 2) {
this->bidirectional = true;
}
Expand Down Expand Up @@ -314,13 +314,11 @@ MyRobotHWInterface::MyRobotHWInterface()
registerInterface(&jnt_state_interface);
registerInterface(&jnt_vel_interface);

private_nh.param<bool>("/mobile_base_controller/enable_pid", enablePID,
false);
enablePID = true;
nh.param<bool>("mobile_base_controller/enable_pid", enablePID, false);
if (enablePID) {
// dummy pid for dynamic reconfigure.
this->reconfig_pid = std::make_shared<control_toolbox::Pid>(1, 0, 0);
this->reconfig_pid->initParam("/mobile_base_controller/", false);
this->reconfig_pid->initParam("mobile_base_controller/", false);
auto gains = this->reconfig_pid->getGains();
for (auto i = 0; i < NUM_JOINTS; i++) {
auto pid = std::make_shared<control_toolbox::Pid>(1, 1, 1);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,13 +90,13 @@ RRBotHWInterface::RRBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model)
: ros_control_boilerplate::GenericHWInterface(nh, urdf_model) {
this->connectServices();

sub0 = nh.subscribe("/mirte/servos/servoRot/position", 1,
sub0 = nh.subscribe("mirte/servos/servoRot/position", 1,
rrbot_control::callbackJoint0);
sub1 = nh.subscribe("/mirte/servos/servoShoulder/position", 1,
sub1 = nh.subscribe("mirte/servos/servoShoulder/position", 1,
rrbot_control::callbackJoint1);
sub2 = nh.subscribe("/mirte/servos/servoElbow/position", 1,
sub2 = nh.subscribe("mirte/servos/servoElbow/position", 1,
rrbot_control::callbackJoint2);
sub3 = nh.subscribe("/mirte/servos/servoWrist/position", 1,
sub3 = nh.subscribe("mirte/servos/servoWrist/position", 1,
rrbot_control::callbackJoint3);

ROS_INFO_NAMED("rrbot_hw_interface", "RRBotHWInterface Ready.");
Expand All @@ -105,20 +105,20 @@ RRBotHWInterface::RRBotHWInterface(ros::NodeHandle &nh, urdf::Model *urdf_model)
void RRBotHWInterface::connectServices() {
ROS_INFO_NAMED("rrbot_hw_interface", "Connecting to the services...");

ros::service::waitForService("/mirte/set_servoRot_servo_angle", -1);
ros::service::waitForService("/mirte/set_servoShoulder_servo_angle", -1);
ros::service::waitForService("/mirte/set_servoElbow_servo_angle", -1);
ros::service::waitForService("/mirte/set_servoWrist_servo_angle", -1);
ros::service::waitForService("mirte/set_servoRot_servo_angle", -1);
ros::service::waitForService("mirte/set_servoShoulder_servo_angle", -1);
ros::service::waitForService("mirte/set_servoElbow_servo_angle", -1);
ros::service::waitForService("mirte/set_servoWrist_servo_angle", -1);
{ // Only mutex when actually writing to class vars.
const std::lock_guard<std::mutex> lock(this->service_clients_mutex);
client0 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoRot_servo_angle", true);
"mirte/set_servoRot_servo_angle", true);
client1 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoShoulder_servo_angle", true);
"mirte/set_servoShoulder_servo_angle", true);
client2 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoElbow_servo_angle", true);
"mirte/set_servoElbow_servo_angle", true);
client3 = nh_.serviceClient<mirte_msgs::SetServoAngle>(
"/mirte/set_servoWrist_servo_angle", true);
"mirte/set_servoWrist_servo_angle", true);
}
ROS_INFO_NAMED("rrbot_hw_interface", "Connected to the services");
}
Expand Down
Loading
Loading