Skip to content

Commit

Permalink
get joint controller topic from rosparam
Browse files Browse the repository at this point in the history
  • Loading branch information
grassjelly committed Aug 14, 2020
1 parent 721ebb8 commit 8e72630
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 13 deletions.
17 changes: 10 additions & 7 deletions champ_base/src/quadruped_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,14 +35,9 @@ QuadrupedController::QuadrupedController(const ros::NodeHandle &node_handle,
leg_controller_(base_),
kinematics_(base_)
{
cmd_vel_subscriber_ = nh_.subscribe("cmd_vel/smooth", 1, &QuadrupedController::cmdVelCallback_, this);
cmd_pose_subscriber_ = nh_.subscribe("cmd_pose", 1, &QuadrupedController::cmdPoseCallback_, this);

joint_states_publisher_ = nh_.advertise<sensor_msgs::JointState>("joint_states", 100);
joint_commands_publisher_ = nh_.advertise<trajectory_msgs::JointTrajectory>("joint_group_position_controller/command", 100);
contacts_publisher_ = nh_.advertise<champ_msgs::Contacts>("foot_contacts", 100);

std::string joint_control_topic = "joint_group_position_controller/command";
std::string knee_orientation;

nh_.getParam("gait/pantograph_leg", gait_config_.pantograph_leg);
nh_.getParam("gait/max_linear_velocity_x", gait_config_.max_linear_velocity_x);
nh_.getParam("gait/max_linear_velocity_y", gait_config_.max_linear_velocity_y);
Expand All @@ -57,6 +52,14 @@ QuadrupedController::QuadrupedController(const ros::NodeHandle &node_handle,
pnh_.getParam("publish_joint_states", publish_joint_states_);
pnh_.getParam("publish_joint_control", publish_joint_control_);
pnh_.getParam("gazebo", in_gazebo_);
pnh_.getParam("joint_controller_topic", joint_control_topic);

joint_commands_publisher_ = nh_.advertise<trajectory_msgs::JointTrajectory>(joint_control_topic, 100);
cmd_vel_subscriber_ = nh_.subscribe("cmd_vel/smooth", 1, &QuadrupedController::cmdVelCallback_, this);
cmd_pose_subscriber_ = nh_.subscribe("cmd_pose", 1, &QuadrupedController::cmdPoseCallback_, this);

joint_states_publisher_ = nh_.advertise<sensor_msgs::JointState>("joint_states", 100);
contacts_publisher_ = nh_.advertise<champ_msgs::Contacts>("foot_contacts", 100);

gait_config_.knee_orientation = knee_orientation.c_str();

Expand Down
12 changes: 6 additions & 6 deletions champ_bringup/launch/bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,12 @@
</node>

<node unless="$(arg lite)" pkg="champ_base" name="champ_controller" type="quadruped_controller_node" output="screen">
<param name="gazebo" value="$(arg gazebo)" />
<param if="$(arg hardware_connected)" name="publish_joint_states" value="false" />
<param unless="$(arg hardware_connected)" name="publish_joint_states" value="true" />
<param name="publish_foot_contacts" value="$(arg publish_foot_contacts)" />
<param name="publish_joint_control" value="$(arg publish_joint_control)" />
<remap from="joint_group_position_controller/command" to="$(arg joint_controller_topic)" />
<param name="gazebo" value="$(arg gazebo)" />
<param if="$(arg hardware_connected)" name="publish_joint_states" value="false" />
<param unless="$(arg hardware_connected)" name="publish_joint_states" value="true" />
<param name="publish_foot_contacts" value="$(arg publish_foot_contacts)" />
<param name="publish_joint_control" value="$(arg publish_joint_control)" />
<param name="joint_controller_topic" value="$(arg joint_controller_topic)" />
</node>
<node unless="$(arg lite)" pkg="champ_base" name="state_estimator" type="state_estimation_node" output="screen"/>

Expand Down

0 comments on commit 8e72630

Please sign in to comment.