update comments, close #2

This commit is contained in:
Wojciech Kwolek 2021-06-17 13:53:51 +02:00
parent 842f753665
commit 5158318fcb
3 changed files with 7 additions and 4 deletions

View File

@ -8,11 +8,12 @@ build/ros2aria/ros2aria: $(SOURCES) $(HEADERS)
build: build/ros2aria/ros2aria
.uploaded: build/ros2aria/ros2aria
# .uploaded: build/ros2aria/ros2aria
upload:
rsync -r . lab1_5@pionier6:~/ros2aria
touch .uploaded
upload: .uploaded
# upload: .uploaded
run: upload
ssh lab1_5@pionier6 -t -- docker run --rm --network=host -it --device /dev/ttyS0 -v /home/lab1_5:/ws irth7/ros2aria-dev /bin/bash /ws/ros2aria/run.sh

View File

@ -22,7 +22,7 @@ Ros2Aria::Ros2Aria()
wheels_pub_ = this->create_publisher<sensor_msgs::msg::JointState>("wheels", 1000);
battery_recharge_state_pub_ = this->create_publisher<std_msgs::msg::Int8>("battery_recharge_state", 10); // TODO: original rosaria latches this - what does that mean and how does it relate to ros2?
battery_recharge_state_pub_ = this->create_publisher<std_msgs::msg::Int8>("battery_recharge_state", 10);
battery_state_of_charge_pub_ = this->create_publisher<std_msgs::msg::Float32>("battery_state_of_charge", 10);
robot_info_pub_ = this->create_publisher<ros2aria_msgs::msg::RobotInfoMsg>("robot_info", 10);

View File

@ -31,7 +31,9 @@ void Ros2Aria::publishState(rclcpp::Time stamp)
robot_info_msg.twist.linear.x = r->getVel() / 1000;
robot_info_msg.twist.linear.y = r->getLatVel() / 1000.0;
robot_info_msg.twist.angular.z = r->getRotVel() * M_PI / 180;
// TODO: actually keep track of robot state
// TODO: actually keep track of robot state (true -> unlocked, false ->
// locked). This requires safety plugin to be implemented
robot_info_msg.state.data = true;
robot_info_msg.clutch.data = r->areMotorsEnabled();
// TODO: actually look for obstacles