Fixed firmware and toid_bot_description
This commit is contained in:
@@ -48,7 +48,7 @@ def generate_launch_description():
|
||||
executable='robot_state_publisher',
|
||||
name='robot_state_publisher',
|
||||
output='screen',
|
||||
parameters=[{'robot_description': Command(['xacro ', default_model_path, ' use_sim:=', use_mock])}]
|
||||
parameters=[{'robot_description': Command(['xacro ', default_model_path, ' use_mock:=', use_mock])}]
|
||||
)
|
||||
|
||||
controller_manager = Node(
|
||||
@@ -108,4 +108,4 @@ def generate_launch_description():
|
||||
joint_state_broadcaster,
|
||||
diffbot_base_controller,
|
||||
rviz_node
|
||||
])
|
||||
])
|
||||
|
||||
@@ -31,6 +31,8 @@ CallbackReturn mg::MgStepperInterface::on_configure(const rclcpp_lifecycle::Stat
|
||||
"Failed to open serial port (Is the stepper driver plugged in)");
|
||||
return CallbackReturn::ERROR;
|
||||
}
|
||||
RCLCPP_INFO(rclcpp::get_logger("MgStepperInterface"),
|
||||
"Configured stepper motor interface");
|
||||
return CallbackReturn::SUCCESS;
|
||||
}
|
||||
|
||||
@@ -45,8 +47,8 @@ std::vector<hardware_interface::StateInterface> mg::MgStepperInterface::export_s
|
||||
|
||||
std::vector<hardware_interface::StateInterface> state_interfaces;
|
||||
state_interfaces.reserve(2);
|
||||
state_interfaces.emplace_back("left_motor", hardware_interface::HW_IF_POSITION, &left_wheel_pos_state);
|
||||
state_interfaces.emplace_back("right_motor", hardware_interface::HW_IF_POSITION, &right_wheel_pos_state);
|
||||
state_interfaces.emplace_back("drivewhl_l_joint", hardware_interface::HW_IF_POSITION, &left_wheel_pos_state);
|
||||
state_interfaces.emplace_back("drivewhl_r_joint", hardware_interface::HW_IF_POSITION, &right_wheel_pos_state);
|
||||
|
||||
return state_interfaces;
|
||||
}
|
||||
@@ -55,8 +57,8 @@ std::vector<hardware_interface::CommandInterface> mg::MgStepperInterface::export
|
||||
|
||||
std::vector<hardware_interface::CommandInterface> command_interfaces;
|
||||
command_interfaces.reserve(2);
|
||||
command_interfaces.emplace_back("left_motor", hardware_interface::HW_IF_VELOCITY, &left_wheel_vel_cmd);
|
||||
command_interfaces.emplace_back("right_motor", hardware_interface::HW_IF_VELOCITY, &right_wheel_vel_cmd);
|
||||
command_interfaces.emplace_back("drivewhl_l_joint", hardware_interface::HW_IF_VELOCITY, &left_wheel_vel_cmd);
|
||||
command_interfaces.emplace_back("drivewhl_r_joint", hardware_interface::HW_IF_VELOCITY, &right_wheel_vel_cmd);
|
||||
|
||||
return command_interfaces;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user