Skip to content

Commit

Permalink
Changed topics and changed head speed to 0
Browse files Browse the repository at this point in the history
Signed-off-by: Juancams <[email protected]>
  • Loading branch information
Juancams committed Nov 5, 2024
1 parent e929797 commit 9429f3c
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 14 deletions.
4 changes: 2 additions & 2 deletions br2_tracking/launch/tracking.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,8 @@ def generate_launch_description():
'use_sim_time': True
}, params_file],
remappings=[
('input_image', '/head_front_camera/rgb/image_raw'),
('joint_state', '/head_controller/state'),
('input_image', '/head_front_camera/image'),
('joint_state', '/head_controller/controller_state'),
('joint_command', '/head_controller/joint_trajectory')
],
output='screen'
Expand Down
24 changes: 12 additions & 12 deletions br2_tracking/src/br2_tracking/HeadController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,10 +82,10 @@ HeadController::on_deactivate(const rclcpp_lifecycle::State & previous_state)
command_msg.points[0].accelerations.resize(2);
command_msg.points[0].positions[0] = 0.0;
command_msg.points[0].positions[1] = 0.0;
command_msg.points[0].velocities[0] = 0.1;
command_msg.points[0].velocities[1] = 0.1;
command_msg.points[0].accelerations[0] = 0.1;
command_msg.points[0].accelerations[1] = 0.1;
command_msg.points[0].velocities[0] = 0.0;
command_msg.points[0].velocities[1] = 0.0;
command_msg.points[0].accelerations[0] = 0.0;
command_msg.points[0].accelerations[1] = 0.0;
command_msg.points[0].time_from_start = rclcpp::Duration(1s);

joint_pub_->publish(command_msg);
Expand Down Expand Up @@ -127,10 +127,10 @@ HeadController::control_sycle()
if (last_command_ == nullptr || (now() - last_command_ts_) > 100ms) {
command_msg.points[0].positions[0] = 0.0;
command_msg.points[0].positions[1] = 0.0;
command_msg.points[0].velocities[0] = 0.1;
command_msg.points[0].velocities[1] = 0.1;
command_msg.points[0].accelerations[0] = 0.1;
command_msg.points[0].accelerations[1] = 0.1;
command_msg.points[0].velocities[0] = 0.0;
command_msg.points[0].velocities[1] = 0.0;
command_msg.points[0].accelerations[0] = 0.0;
command_msg.points[0].accelerations[1] = 0.0;
command_msg.points[0].time_from_start = rclcpp::Duration(1s);
} else {
double control_pan = pan_pid_.get_output(last_command_->pan);
Expand All @@ -139,10 +139,10 @@ HeadController::control_sycle()
command_msg.points[0].positions[0] = last_state_->feedback.positions[0] - control_pan;
command_msg.points[0].positions[1] = last_state_->feedback.positions[1] - control_tilt;

command_msg.points[0].velocities[0] = 0.5;
command_msg.points[0].velocities[1] = 0.5;
command_msg.points[0].accelerations[0] = 0.5;
command_msg.points[0].accelerations[1] = 0.5;
command_msg.points[0].velocities[0] = 0.0;
command_msg.points[0].velocities[1] = 0.0;
command_msg.points[0].accelerations[0] = 0.0;
command_msg.points[0].accelerations[1] = 0.0;
}

joint_pub_->publish(command_msg);
Expand Down

0 comments on commit 9429f3c

Please sign in to comment.